1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-01 18:32:37 +02:00

Almost compiles ...

This commit is contained in:
Mitch Bradley
2021-05-19 20:36:55 -10:00
parent 1928f4eab6
commit 195e15c40c
16 changed files with 214 additions and 166 deletions

View File

@@ -93,6 +93,7 @@ void run_once();
// Weak definitions that can be overridden // Weak definitions that can be overridden
void machine_init(); void machine_init();
void display_init();
bool user_defined_homing(uint8_t cycle_mask); bool user_defined_homing(uint8_t cycle_mask);
// weak definitions in MotionControl.cpp // weak definitions in MotionControl.cpp

View File

@@ -413,7 +413,7 @@ bool __attribute__((weak)) limitsCheckTravel(float* target) {
} }
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) { bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
return (limit_pins[axis][gang_index] != UNDEFINED_PIN); return (LimitPins[axis][gang_index]->get() != Pin::UNDEFINED);
} }
bool __attribute__((weak)) user_defined_homing(uint8_t cycle_mask) { bool __attribute__((weak)) user_defined_homing(uint8_t cycle_mask) {

View File

@@ -422,7 +422,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
} }
// Setup and queue probing motion. Auto cycle-start should not start the cycle. // Setup and queue probing motion. Auto cycle-start should not start the cycle.
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Found"); grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Found");
mc_line_kins(target, pl_data, gc_state.position); cartesian_to_motors(target, pl_data, gc_state.position);
// Activate the probing state monitor in the stepper module. // Activate the probing state monitor in the stepper module.
sys_probe_state = ProbeState::Active; sys_probe_state = ProbeState::Active;
// Perform probing cycle. Wait here until probe is triggered or motion completes. // Perform probing cycle. Wait here until probe is triggered or motion completes.

View File

@@ -35,7 +35,6 @@
namespace Motors { namespace Motors {
void Motor::debug_message() {} void Motor::debug_message() {}
Motor::Motor(uint8_t axis_index) : _axis_index(axis_index % MAX_AXES), _dual_axis_index(axis_index / MAX_AXES) {}
bool Motor::test() { return true; }; // true = OK bool Motor::test() { return true; }; // true = OK

View File

@@ -127,6 +127,7 @@ namespace Motors {
} }
void RcServo::read_settings() { void RcServo::read_settings() {
#ifdef LATER
if (bitnum_istrue(dir_invert_mask->get(), _axis_index)) { if (bitnum_istrue(dir_invert_mask->get(), _axis_index)) {
// swap the pwm values // swap the pwm values
_pwm_pulse_min = SERVO_MAX_PULSE * (1.0 + (1.0 - rc_servo_cal_min->get())); _pwm_pulse_min = SERVO_MAX_PULSE * (1.0 + (1.0 - rc_servo_cal_min->get()));
@@ -136,6 +137,7 @@ namespace Motors {
_pwm_pulse_min = SERVO_MIN_PULSE * rc_servo_cal_min->get(); _pwm_pulse_min = SERVO_MIN_PULSE * rc_servo_cal_min->get();
_pwm_pulse_max = SERVO_MAX_PULSE * rc_servo_cal_max->get(); _pwm_pulse_max = SERVO_MAX_PULSE * rc_servo_cal_max->get();
} }
#endif
} }
// Configuration registration // Configuration registration

View File

@@ -228,7 +228,7 @@ namespace Motors {
There are ton of settings. I'll start by grouping then into modes for now. There are ton of settings. I'll start by grouping then into modes for now.
Many people will want quiet and stallgaurd homing. Stallguard only run in Many people will want quiet and stallgaurd homing. Stallguard only run in
Coolstep mode, so it will need to switch to Coolstep when homing Coolstep mode, so it will need to switch to Coolstep when homing
*/ */
void TrinamicDriver::set_mode(bool isHoming) { void TrinamicDriver::set_mode(bool isHoming) {
if (_has_errors) { if (_has_errors) {
return; return;
@@ -266,7 +266,7 @@ namespace Motors {
tmcstepper->THIGH(calc_tstep(feedrate, 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(constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63)); tmcstepper->sgt(constrain(axis_settings[axis_index()]->stallguard->get(), -64, 63));
break; break;
} }
default: default:
@@ -295,7 +295,7 @@ namespace Motors {
tmcstepper->stallguard(), tmcstepper->stallguard(),
tmcstepper->sg_result(), tmcstepper->sg_result(),
feedrate, feedrate,
constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63)); constrain(axis_settings[axis_index()]->stallguard->get(), -64, 63));
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();
@@ -309,7 +309,7 @@ namespace Motors {
// grbl_msg_sendf(CLIENT_SERIAL, // grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info, // MsgLevel::Info,
// "%s Status Register %08x GSTAT %02x", // "%s Status Register %08x GSTAT %02x",
// reportAxisNameMsg(_axis_index, _dual_axis_index), // reportAxisNameMsg(axis_index(), dual_axis_index()),
// status.sr, // status.sr,
// tmcstepper->GSTAT()); // tmcstepper->GSTAT());
} }

View File

@@ -56,12 +56,14 @@ const double TRINAMIC_UART_FCLK = 12700000.0; // Internal clock Approx (Hz) use
# define TMC_UART UART_NUM_2 # define TMC_UART UART_NUM_2
#endif #endif
#ifndef TMC_UART_RX #ifdef LATER
# ifndef TMC_UART_RX
# define TMC_UART_RX UNDEFINED_PIN # define TMC_UART_RX UNDEFINED_PIN
#endif # endif
#ifndef TMC_UART_TX # ifndef TMC_UART_TX
# define TMC_UART_TX UNDEFINED_PIN # define TMC_UART_TX UNDEFINED_PIN
# endif
#endif #endif
extern Uart tmc_serial; extern Uart tmc_serial;
@@ -79,28 +81,7 @@ namespace Motors {
private: private:
static bool _uart_started; static bool _uart_started;
public: uint32_t calc_tstep(float speed, float percent);
TrinamicUartDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint16_t driver_part_number,
float r_senseS,
uint8_t address);
void config_message();
void hw_serial_init();
void init();
void set_mode();
void read_settings();
void debug_message();
bool set_homing_mode(bool is_homing) override;
void set_disable(bool disable) override;
uint8_t addr;
private:
uint32_t calc_tstep(float speed, float percent); //TODO: see if this is useful/used.
TMC2209Stepper* tmcstepper; // all other driver types are subclasses of this one TMC2209Stepper* tmcstepper; // all other driver types are subclasses of this one
TrinamicUartMode _homing_mode; TrinamicUartMode _homing_mode;
@@ -109,6 +90,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;
TrinamicUartMode _mode = TrinamicUartMode::None; TrinamicUartMode _mode = TrinamicUartMode::None;
bool test(); bool test();
void set_mode(bool isHoming); void set_mode(bool isHoming);
@@ -129,7 +115,54 @@ namespace Motors {
static void readSgTask(void*); static void readSgTask(void*);
protected: protected:
// void config_message() override; void config_message() override;
public:
TrinamicUartDriver(uint16_t driver_part_number) : TrinamicUartDriver(driver_part_number, get_next_index()) {}
TrinamicUartDriver(uint16_t driver_part_number, uint8_t address);
void init() override;
void read_settings() override;
bool set_homing_mode(bool is_homing) override;
void set_disable(bool disable) override;
void debug_message();
bool hw_serial_init();
uint8_t _addr;
// Configuration handlers:
void validate() const override { StandardStepper::validate(); }
void handle(Configuration::HandlerBase& handler) override {
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);
}
// Name of the configurable. Must match the name registered in the cpp file.
const char* name() const override { return "trinamic_uart"; }
}; };
class TMC2008 : public TrinamicUartDriver {
public:
TMC2008() : TrinamicUartDriver(2008) {}
// Name of the configurable. Must match the name registered in the cpp file.
const char* name() const override { return "tmc_2008"; }
};
class TMC2009 : public TrinamicUartDriver {
public:
TMC2009() : TrinamicUartDriver(2009) {}
// Name of the configurable. Must match the name registered in the cpp file.
const char* name() const override { return "tmc_2009"; }
};
} }

View File

@@ -23,6 +23,7 @@
*/ */
#include "TrinamicUartDriver.h" #include "TrinamicUartDriver.h"
#include "../MachineConfig.h"
#include <TMCStepper.h> #include <TMCStepper.h>
@@ -32,56 +33,48 @@ namespace Motors {
bool TrinamicUartDriver::_uart_started = false; bool TrinamicUartDriver::_uart_started = false;
TrinamicUartDriver* TrinamicUartDriver::List = NULL; // a static ist of all drivers for stallguard reporting TrinamicUartDriver* TrinamicUartDriver::List = NULL; // a static list of all drivers for stallguard reporting
uint8_t TrinamicUartDriver::get_next_index() {
static uint8_t index = 1; // they start at 1
return index++;
}
/* HW Serial Constructor. */ /* HW Serial Constructor. */
TrinamicUartDriver::TrinamicUartDriver( TrinamicUartDriver::TrinamicUartDriver(uint16_t driver_part_number, uint8_t addr) :
uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin, uint16_t driver_part_number, float r_sense, uint8_t addr) : StandardStepper(), _driver_part_number(driver_part_number), _addr(addr) {}
StandardStepper(axis_index, step_pin, dir_pin, disable_pin) {
_driver_part_number = driver_part_number;
_has_errors = false;
_r_sense = r_sense;
this->addr = addr;
void TrinamicUartDriver::init() {
if (!_uart_started) { if (!_uart_started) {
#ifdef LATER
tmc_serial.setPins(TMC_UART_TX, TMC_UART_RX); tmc_serial.setPins(TMC_UART_TX, TMC_UART_RX);
#endif
tmc_serial.begin(115200, Uart::Data::Bits8, Uart::Stop::Bits1, Uart::Parity::None); tmc_serial.begin(115200, Uart::Data::Bits8, Uart::Stop::Bits1, Uart::Parity::None);
_uart_started = true; _uart_started = true;
} }
hw_serial_init(); _has_errors = hw_serial_init();
link = List; link = List;
List = this; List = this;
// Display the stepper library version message once, before the first
// TMC config message. Link is NULL for the first TMC instance.
if (!link) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "TMCStepper Library Ver. 0x%06x", TMCSTEPPER_VERSION);
} }
void TrinamicUartDriver::hw_serial_init() {
if (_driver_part_number == 2209)
tmcstepper = new TMC2209Stepper(&tmc_serial, _r_sense, addr);
else {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unsupported Trinamic motor p/n:%d", _driver_part_number);
return;
}
}
void TrinamicUartDriver ::init() {
if (_has_errors) { if (_has_errors) {
return; return;
} }
init_step_dir_pins(); // from StandardStepper
config_message(); config_message();
tmcstepper->begin(); tmcstepper->begin();
_has_errors = !test(); // Try communicating with motor. Prints an error if there is a problem. _has_errors = !test(); // Try communicating with motor. Prints an error if there is a problem.
/* If communication with the driver is working, read the read_settings(); // pull info from settings
main settings, apply new driver settings and then read
them back. */
if (!_has_errors) { //TODO: verify if this is the right way to set the Irun/IHold and microsteps.
read_settings();
set_mode(false); set_mode(false);
}
// After initializing all of the TMC drivers, create a task to // After initializing all of the TMC drivers, create a task to
// display StallGuard data. List == this for the final instance. // display StallGuard data. List == this for the final instance.
@@ -93,11 +86,19 @@ namespace Motors {
1, // priority 1, // priority
NULL, NULL,
SUPPORT_TASK_CORE // must run the task on same core SUPPORT_TASK_CORE // must run the task on same core
// core
); );
} }
} }
bool TrinamicUartDriver::hw_serial_init() {
if (_driver_part_number == 2209) {
tmcstepper = new TMC2209Stepper(&tmc_serial, _r_sense, _addr);
return false;
}
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unsupported Trinamic motor p/n:%d", _driver_part_number);
return true;
}
/* /*
This is the startup message showing the basic definition. This is the startup message showing the basic definition.
*/ */
@@ -105,35 +106,41 @@ namespace Motors {
grbl_msg_sendf(CLIENT_SERIAL, grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info, MsgLevel::Info,
"%s motor Trinamic TMC%d Step:%s Dir:%s Disable:%s UART%d Rx:%s Tx:%s Addr:%d R:%0.3f %s", "%s motor Trinamic TMC%d Step:%s Dir:%s Disable:%s UART%d Rx:%s Tx:%s Addr:%d R:%0.3f %s",
reportAxisNameMsg(_axis_index, _dual_axis_index), reportAxisNameMsg(axis_index(), dual_axis_index()),
_driver_part_number, _driver_part_number,
pinName(_step_pin).c_str(), _step_pin.name().c_str(),
pinName(_dir_pin).c_str(), _dir_pin.name().c_str(),
pinName(_disable_pin).c_str(), _disable_pin.name().c_str(),
TMC_UART, TMC_UART,
#ifdef LATER
pinName(TMC_UART_RX), pinName(TMC_UART_RX),
pinName(TMC_UART_TX), pinName(TMC_UART_TX),
this->addr, #else
0,
0,
#endif
_addr,
_r_sense, _r_sense,
reportAxisLimitsMsg(_axis_index)); reportAxisLimitsMsg(axis_index()));
} }
bool TrinamicUartDriver::test() { bool TrinamicUartDriver::test() {
if (_has_errors) { if (_has_errors) {
return false; return false;
} }
switch (tmcstepper->test_connection()) { switch (tmcstepper->test_connection()) {
case 1: case 1:
grbl_msg_sendf(CLIENT_SERIAL, grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info, MsgLevel::Info,
"%s driver test failed. Check connection", "%s driver test failed. Check connection",
reportAxisNameMsg(_axis_index, _dual_axis_index)); reportAxisNameMsg(axis_index(), dual_axis_index()));
return false; return false;
case 2: case 2:
grbl_msg_sendf(CLIENT_SERIAL, grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info, MsgLevel::Info,
"%s driver test failed. Check motor power", "%s driver test failed. Check motor power",
reportAxisNameMsg(_axis_index, _dual_axis_index)); reportAxisNameMsg(axis_index(), dual_axis_index()));
return false; return false;
default: default:
// driver responded, so check for other errors from the DRV_STATUS register // driver responded, so check for other errors from the DRV_STATUS register
@@ -160,7 +167,7 @@ namespace Motors {
return false; return false;
} }
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s driver test passed", reportAxisNameMsg(_axis_index, _dual_axis_index)); grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s driver test passed", reportAxisNameMsg(axis_index(), dual_axis_index()));
return true; return true;
} }
} }
@@ -176,23 +183,21 @@ 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);
// grbl_msg_sendf(CLIENT_SERIAL, init_step_dir_pins();
// MsgLevel::Info,
// "Setting current of driver %s, target: %u, read irun: %d, hold percent: %f, usteps: %d",
// reportAxisNameMsg(_axis_index, _dual_axis_index), run_i_ma, tmcstepper->rms_current(), hold_i_percent, axis_settings[_axis_index]->microsteps->get());
} }
bool TrinamicUartDriver::set_homing_mode(bool isHoming) { bool TrinamicUartDriver::set_homing_mode(bool isHoming) {
@@ -215,27 +220,26 @@ namespace Motors {
if (newMode == _mode) { if (newMode == _mode) {
return; return;
} }
_mode = newMode; _mode = newMode;
switch (_mode) { switch (_mode) {
case TrinamicUartMode ::StealthChop: case TrinamicUartMode ::StealthChop:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop"); //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop");
tmcstepper->en_spreadCycle(false); tmcstepper->en_spreadCycle(false);
tmcstepper->pwm_autoscale(true); tmcstepper->pwm_autoscale(true);
break; break;
case TrinamicUartMode ::CoolStep: case TrinamicUartMode ::CoolStep:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep"); //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep");
// tmcstepper->en_pwm_mode(false); //TODO: check if this is present in TMC2208/09 // tmcstepper->en_pwm_mode(false); //TODO: check if this is present in TMC2208/09
tmcstepper->en_spreadCycle(true); tmcstepper->en_spreadCycle(true);
tmcstepper->pwm_autoscale(false); tmcstepper->pwm_autoscale(false);
break; break;
case TrinamicUartMode ::StallGuard: //TODO: check all configurations for stallguard case TrinamicUartMode ::StallGuard: //TODO: check all configurations for stallguard
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard"); //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
tmcstepper->en_spreadCycle(false); tmcstepper->en_spreadCycle(false);
tmcstepper->pwm_autoscale(false); tmcstepper->pwm_autoscale(false);
tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0)); tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
tmcstepper->SGTHRS(constrain(axis_settings[_axis_index]->stallguard->get(), 0, 255)); tmcstepper->SGTHRS(constrain(axis_settings[axis_index()]->stallguard->get(), 0, 255));
break; break;
default: default:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unknown Trinamic mode:d", _mode); grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unknown Trinamic mode:d", _mode);
@@ -259,10 +263,10 @@ namespace Motors {
grbl_msg_sendf(CLIENT_SERIAL, grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info, MsgLevel::Info,
"%s SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d", "%s SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
reportAxisNameMsg(_axis_index, _dual_axis_index), reportAxisNameMsg(axis_index(), dual_axis_index()),
tmcstepper->SG_RESULT(), // tmcstepper->sg_result(), tmcstepper->SG_RESULT(), // tmcstepper->sg_result(),
feedrate, feedrate,
axis_settings[_axis_index]->stallguard->get()); constrain(axis_settings[axis_index()]->stallguard->get(), -64, 63));
TMC2208_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits. TMC2208_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
status.sr = tmcstepper->DRV_STATUS(); status.sr = tmcstepper->DRV_STATUS();
@@ -272,6 +276,13 @@ namespace Motors {
report_short_to_ground(status); report_short_to_ground(status);
report_over_temp(status); report_over_temp(status);
report_short_to_ps(status); report_short_to_ps(status);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "%s Status Register %08x GSTAT %02x",
// reportAxisNameMsg(axis_index(), dual_axis_index()),
// status.sr,
// tmcstepper->GSTAT());
} }
// calculate a tstep from a rate // calculate a tstep from a rate
@@ -279,8 +290,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 TrinamicUartDriver::calc_tstep(float speed, float percent) { uint32_t TrinamicUartDriver::calc_tstep(float speed, float percent) {
float 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() * (float)(256 / axis_settings[_axis_index]->microsteps->get());
tstep = TRINAMIC_UART_FCLK / tstep * percent / 100.0; tstep = TRINAMIC_UART_FCLK / tstep * percent / 100.0;
return static_cast<uint32_t>(tstep); return static_cast<uint32_t>(tstep);
@@ -299,7 +309,7 @@ namespace Motors {
_disabled = disable; _disabled = disable;
digitalWrite(_disable_pin, _disabled); _disable_pin.write(_disabled);
#ifdef USE_TRINAMIC_ENABLE #ifdef USE_TRINAMIC_ENABLE
if (_disabled) { if (_disabled) {
@@ -316,73 +326,18 @@ namespace Motors {
// This would be for individual motors, not the single pin for all motors. // This would be for individual motors, not the single pin for all motors.
} }
// =========== Reporting functions ========================
bool TrinamicUartDriver::report_open_load(TMC2208_n ::DRV_STATUS_t status) {
if (status.ola || status.olb) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver open load A:%s B:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
status.ola ? "Y" : "N",
status.olb ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_short_to_ground(TMC2208_n ::DRV_STATUS_t status) {
if (status.s2ga || status.s2gb) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver shorted coil A:%s B:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
status.s2ga ? "Y" : "N",
status.s2gb ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_over_temp(TMC2208_n ::DRV_STATUS_t status) {
if (status.ot || status.otpw) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver temp Warning:%s Fault:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
status.otpw ? "Y" : "N",
status.ot ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_short_to_ps(TMC2208_n ::DRV_STATUS_t status) {
// check for short to power supply
if ((status.sr & bit(12)) || (status.sr & bit(13))) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver short vsa:%s vsb:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
(status.sr & bit(12)) ? "Y" : "N",
(status.sr & bit(13)) ? "Y" : "N");
return true;
}
return false; // no error
}
// Prints StallGuard data that is useful for tuning. // Prints StallGuard data that is useful for tuning.
void TrinamicUartDriver::readSgTask(void* pvParameters) { void TrinamicUartDriver::readSgTask(void* pvParameters) {
TickType_t xLastWakeTime; TickType_t xLastWakeTime;
const TickType_t xreadSg = 200; // in ticks (typically ms) const TickType_t xreadSg = 200; // in ticks (typically ms)
auto n_axis = number_axis->get(); auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time. xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies while (true) { // don't ever return from this or the task dies
if (stallguard_debug_mask->get() != 0) { if (stallguard_debug_mask->get() != 0) {
if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) { if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) {
for (TrinamicUartDriver* p = List; p; p = p->link) { for (TrinamicUartDriver* p = List; p; p = p->link) {
if (bitnum_istrue(stallguard_debug_mask->get(), p->_axis_index)) { if (bitnum_istrue(stallguard_debug_mask->get(), p->axis_index())) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SG:%d", stallguard_debug_mask->get()); //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SG:%d", stallguard_debug_mask->get());
p->debug_message(); p->debug_message();
} }
@@ -398,4 +353,65 @@ namespace Motors {
#endif #endif
} }
} }
// =========== Reporting functions ========================
bool TrinamicUartDriver::report_open_load(TMC2208_n ::DRV_STATUS_t status) {
if (status.ola || status.olb) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver Open Load a:%s b:%s",
reportAxisNameMsg(axis_index(), dual_axis_index()),
status.ola ? "Y" : "N",
status.olb ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_short_to_ground(TMC2208_n ::DRV_STATUS_t status) {
if (status.s2ga || status.s2gb) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver Short Coil a:%s b:%s",
reportAxisNameMsg(axis_index(), dual_axis_index()),
status.s2ga ? "Y" : "N",
status.s2gb ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_over_temp(TMC2208_n ::DRV_STATUS_t status) {
if (status.ot || status.otpw) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver Temp Warning:%s Fault:%s",
reportAxisNameMsg(axis_index(), dual_axis_index()),
status.otpw ? "Y" : "N",
status.ot ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_short_to_ps(TMC2208_n ::DRV_STATUS_t status) {
// check for short to power supply
if ((status.sr & bit(12)) || (status.sr & bit(13))) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver Short vsa:%s vsb:%s",
reportAxisNameMsg(axis_index(), dual_axis_index()),
(status.sr & bit(12)) ? "Y" : "N",
(status.sr & bit(13)) ? "Y" : "N");
return true;
}
return false; // no error
}
// Configuration registration
namespace {
MotorFactory::InstanceBuilder<TMC2008> registration_2008("tmc_2008");
MotorFactory::InstanceBuilder<TMC2009> registration_2009("tmc_2009");
}
} }

View File

@@ -436,7 +436,9 @@ Error motor_disable(const char* value, WebUI::AuthenticationLevel auth_level, We
} }
} }
} }
#ifdef LATER
motors_set_disable(true, convertedValue); motors_set_disable(true, convertedValue);
#endif
return Error::Ok; return Error::Ok;
} }

View File

@@ -166,12 +166,12 @@ SDState get_sd_state(bool refresh) {
//refresh content if card was removed //refresh content if card was removed
if (SD.begin((GRBL_SPI_SS == -1) ? SS : GRBL_SPI_SS, SPI, GRBL_SPI_FREQ, "/sd", 2)) { if (SD.begin((GRBL_SPI_SS == -1) ? SS : GRBL_SPI_SS, SPI, GRBL_SPI_FREQ, "/sd", 2)) {
if (SD.cardSize() > 0) { if (SD.cardSize() > 0) {
sd_state = SDCARD_IDLE; sd_state = SDState::Idle;
} }
} }
return sd_state; return sd_state;
} else { } else {
return SDCARD_NOT_PRESENT; return SDState::NotPresent;
} }
} }

View File

@@ -150,7 +150,6 @@ static uint8_t getClientChar(uint8_t* data) {
void clientCheckTask(void* pvParameters) { void clientCheckTask(void* pvParameters) {
uint8_t data = 0; uint8_t data = 0;
uint8_t client; // who sent the data uint8_t client; // who sent the data
static UBaseType_t uxHighWaterMark = 0;
while (true) { // run continuously while (true) { // run continuously
// Pick off realtime command characters directly from the serial stream. These characters are // Pick off realtime command characters directly from the serial stream. These characters are
// not passed into the main buffer, but these set system state flag bits for realtime execution. // not passed into the main buffer, but these set system state flag bits for realtime execution.
@@ -185,12 +184,11 @@ void clientCheckTask(void* pvParameters) {
#endif #endif
vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK #ifdef DEBUG_TASK_STACK
static UBaseType_t uxHighWaterMark = 0;
reportTaskStackSize(uxHighWaterMark); reportTaskStackSize(uxHighWaterMark);
#endif #endif
} }
}
void client_reset_read_buffer(uint8_t client) { void client_reset_read_buffer(uint8_t client) {
for (uint8_t client_num = 0; client_num < CLIENT_COUNT; client_num++) { for (uint8_t client_num = 0; client_num < CLIENT_COUNT; client_num++) {

View File

@@ -196,9 +196,11 @@ static bool checkStartupLine(char* value) {
} }
static bool postMotorSetting(char* value) { static bool postMotorSetting(char* value) {
#ifdef LATER
if (!value) { if (!value) {
motors_read_settings(); motors_read_settings();
} }
#endif
return true; return true;
} }
@@ -213,7 +215,6 @@ static bool checkSpindleChange(char* val) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Spindle turned off with setting change"); grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Spindle turned off with setting change");
} }
gc_state.spindle_speed = 0; // Set S value to 0 gc_state.spindle_speed = 0; // Set S value to 0
spindle->deinit(); // old spindle
Spindles::Spindle::select(); // get new spindle Spindles::Spindle::select(); // get new spindle
return true; return true;
} }

View File

@@ -30,8 +30,10 @@
namespace Spindles { namespace Spindles {
H2A::H2A() : VFD() { H2A::H2A() : VFD() {
#ifdef LATER
_baudrate = 19200; _baudrate = 19200;
_parity = Uart::Parity::Even; _parity = Uart::Parity::Even;
#endif
} }
void H2A::direction_command(SpindleState mode, ModbusCommand& data) { void H2A::direction_command(SpindleState mode, ModbusCommand& data) {

View File

@@ -86,10 +86,5 @@ namespace Spindles {
_pwm_chan_num = 0; // Channel 0 is reserved for spindle use _pwm_chan_num = 0; // Channel 0 is reserved for spindle use
} }
#endif
void Laser::deinit() { }
stop();
ledcDetachPin(_output_pin.getNative(Pin::Capabilities::PWM));
_output_pin.setAttr(Pin::Attr::Input);
_enable_pin.setAttr(Pin::Attr::Input);
}

View File

@@ -37,7 +37,6 @@ namespace Spindles {
bool isRateAdjusted() override; bool isRateAdjusted() override;
void config_message() override; void config_message() override;
void get_pins_and_settings() override; void get_pins_and_settings() override;
void deinit() override;
virtual ~Laser() {} virtual ~Laser() {}
}; };

View File

@@ -267,6 +267,6 @@ namespace Spindles {
ledcDetachPin(_output_pin.getNative(Pin::Capabilities::PWM)); ledcDetachPin(_output_pin.getNative(Pin::Capabilities::PWM));
_output_pin.setAttr(Pin::Attr::Input); _output_pin.setAttr(Pin::Attr::Input);
_enable_pin.setAttr(Pin::Attr::Input); _enable_pin.setAttr(Pin::Attr::Input);
_dir_pin.setAttr(Pin::Attr::Input); _direction_pin.setAttr(Pin::Attr::Input);
} }
} }