Skip to content

Commit 3c6c3fe

Browse files
bdringmeMitchBradleymarcow1601atlaste
authored
Devt (#971)
* changing to EXTENDED type from GRBL type to prevent sender issues when running 1585 * Oled2 (#834) * WIP * WIP * Update platformio.ini * WIP * Cleanup * Update platformio.ini * Turn off soft limits with max travel (#836) #831 * Yalang YL620 VFD (#838) * New SpindleType YL620 Files for new SpindleType Yalang 620. So far the contents are a duplicate of H2ASpindle.h and H2ASpindle.cpp * Added register documentation and implemented read and write data packets * Some fixes, mostly regarding RX packet length * OLED and Other Updates (#844) * publish * Updates - CoreXY and OLED - Moved position calculation out of report_realtime_status(...) so other functions can access it. - Added a function to check if a limit switch is defined - CoreXY fixed bug in forward kinematics when midtbot is used. - Modified OLED display. * Cleanup for PR * Delete midtbot_x2.h * Incorporated PR 846 - Some OLED cleanup - verified correct forward kinematics on MidTbot * Pio down rev (#850) * Update platformio.ini * Update Grbl.h * Use local UART driver not HardwareSerial (#857) * Use local UART driver not HardwareSerial The HardwareSerial driver is broken in Arduino framework versions 1.0.5 and 1.0.6 . espressif/arduino-esp32#5005 Instead of waiting for a fix, I wrote a very simple UART driver that does exactly what we need with no unnecessary bells and whistles to cause problems. * Added missing files, changed method signatures The methods implemented by the UART class now have the same signatures as the HardwareSerial class, so it will be easy to switch back if we need to. * Incorporated suggestions from Stefan * Fixed TX_IDLE_NUM bug reported by mstrens * Quick test for Bf: problem This is not the final solution. * Fixed stupid typo in last commit * Another test - check for client_buffer space * Use the esp-idf uart driver You can revert to the direct driver for testing by defining DIRECT_UART * Uart class now supports VFD and TMC * data bits, stop bits, parity as enum classes The constants for data bits, stop bits, and parity were changed to enum classes so the compiler can check for argument order mismatches. * Set half duplex after uart init * Init TMC UART only once * rx/tx pin order mixup, missing _uart_started * Test: use Arduino Serial This reverts to the Arduino serial driver for UI communication, leaving the VFS comms on the Uart class on top of the esp_idf UART driver. You can switch back and forth with the define REVERT_TO_SERIAL line in Serial.cpp * REVERT_TO_ARDUINO_SERIAL off by default * Added debug messages * Update Grbl.h * Update platformio.ini Co-authored-by: bdring <[email protected]> * Fixed spindle sync for all VFD spindles (#868) * Implemented H2A spindle sync fix. Untested. * Changed the spindle sync fix to be in the VFD code. * Update Grbl.h Co-authored-by: Stefan de Bruijn <[email protected]> Co-authored-by: bdring <[email protected]> * New jog fix (#872) * Applied 741 to new Devt * Make kinematics routines weak to eliminate ifdefs * Fixed warning * Update build date Co-authored-by: bdring <[email protected]> * need to override set_rpm * trying set_rpm override * it turns on! * start/stop and set speed all working * cleanup * fixing machine.h * fix .gitignore *&vi .gitignore didn't work anyway * forgot to get rid of hard coded max_freq, fixed now * changed 'speed' to 'freq' * reverting platformio.ini * minor readme update * removed debug msg * Big kinematics cleanup (#875) * Applied 741 to new Devt * Make kinematics routines weak to eliminate ifdefs * Fixed warning * Big kinematics cleanup * Cleanup * no isCancelled arg for jog_execute; return it instead * WIP * Made OLED compliant with new kinematics * Added system_get_mpos * system_get_mpos() returns float* * WIP * Cleanup after testing - Had MPos and WPos text on OLED backwards. - Added my cartesian test def - Will remove test defs before merging to devt. * Cleanup of remaining user optional code. * Fixed delta kinematics loop ending early. * Account for jog cancel in saved motor positions * Update Grbl.h Co-authored-by: bdring <[email protected]> * Add the Root 4 Lite CNC machine to the Machines folder (#886) * update for the Root 4 Lite * Return machine.h to use test_drive.hy * Removed some machine definitions Co-authored-by: bdring <[email protected]> * YL620_Fix (#941) * YL620_Fix Fix per ... #926 (comment) Added CNC_xPro machine def * Update Grbl.h * Delete CNC_xPRO_V5_XYYZ_PWM_NO.h * fixes for RPM * note * fixed rx length * fix smell and update readme * clang format * trying to fix newlines * trying to fix newlines part 2 * fix cast issue * fixed spinup spindown swap. * Core xy soft limits (#960) * Soft limit fix * Update Grbl.h * Increase serial task stack size (#970) * Increase stack size - Also changed defaults of trinamic motor currents * Update Grbl.h * 5160 class fix (#981) * Fixed class inheritance * Update date Co-authored-by: me <[email protected]> Co-authored-by: Mitch Bradley <[email protected]> Co-authored-by: marcosprojects <[email protected]> Co-authored-by: Stefan de Bruijn <[email protected]> Co-authored-by: Stefan de Bruijn <[email protected]> Co-authored-by: Pete <[email protected]> Co-authored-by: Jesse Schoch <[email protected]>
1 parent 5316c64 commit 3c6c3fe

File tree

12 files changed

+126
-75
lines changed

12 files changed

+126
-75
lines changed

Diff for: Grbl_Esp32/Custom/CoreXY.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -312,11 +312,6 @@ void kinematics_post_homing() {
312312
memcpy(gc_state.position, last_cartesian, n_axis * sizeof(last_cartesian[0]));
313313
}
314314

315-
// this is used used by Limits.cpp to see if the range of the machine is exceeded.
316-
bool limitsCheckTravel(float* target) {
317-
return false;
318-
}
319-
320315
void user_m30() {}
321316

322317
// ================ Local Helper functions =================

Diff for: Grbl_Esp32/src/Defaults.h

+12-12
Original file line numberDiff line numberDiff line change
@@ -386,43 +386,43 @@
386386

387387
// ========== Motor current (SPI Drivers ) =============
388388
#ifndef DEFAULT_X_CURRENT
389-
# define DEFAULT_X_CURRENT 0.25 // $140 current in amps (extended set)
389+
# define DEFAULT_X_CURRENT 0.8 // $140 current in amps (extended set)
390390
#endif
391391
#ifndef DEFAULT_Y_CURRENT
392-
# define DEFAULT_Y_CURRENT 0.25 // $141 current in amps (extended set)
392+
# define DEFAULT_Y_CURRENT 0.8 // $141 current in amps (extended set)
393393
#endif
394394
#ifndef DEFAULT_Z_CURRENT
395-
# define DEFAULT_Z_CURRENT 0.25 // $142 current in amps (extended set)
395+
# define DEFAULT_Z_CURRENT 0.8 // $142 current in amps (extended set)
396396
#endif
397397
#ifndef DEFAULT_A_CURRENT
398-
# define DEFAULT_A_CURRENT 0.25 // $143 current in amps (extended set)
398+
# define DEFAULT_A_CURRENT 0.8 // $143 current in amps (extended set)
399399
#endif
400400
#ifndef DEFAULT_B_CURRENT
401-
# define DEFAULT_B_CURRENT 0.25 // $144 current in amps (extended set)
401+
# define DEFAULT_B_CURRENT 0.8 // $144 current in amps (extended set)
402402
#endif
403403
#ifndef DEFAULT_C_CURRENT
404-
# define DEFAULT_C_CURRENT 0.25 // $145 current in amps (extended set)
404+
# define DEFAULT_C_CURRENT 0.8 // $145 current in amps (extended set)
405405
#endif
406406

407407
// ========== Motor hold current (SPI Drivers ) =============
408408

409409
#ifndef DEFAULT_X_HOLD_CURRENT
410-
# define DEFAULT_X_HOLD_CURRENT 0.125 // $150 current in amps (extended set)
410+
# define DEFAULT_X_HOLD_CURRENT 0.4 // $150 current in amps (extended set)
411411
#endif
412412
#ifndef DEFAULT_Y_HOLD_CURRENT
413-
# define DEFAULT_Y_HOLD_CURRENT 0.125 // $151 current in amps (extended set)
413+
# define DEFAULT_Y_HOLD_CURRENT 0.4 // $151 current in amps (extended set)
414414
#endif
415415
#ifndef DEFAULT_Z_HOLD_CURRENT
416-
# define DEFAULT_Z_HOLD_CURRENT 0.125 // $152 current in amps (extended set)
416+
# define DEFAULT_Z_HOLD_CURRENT 0.4 // $152 current in amps (extended set)
417417
#endif
418418
#ifndef DEFAULT_A_HOLD_CURRENT
419-
# define DEFAULT_A_HOLD_CURRENT 0.125 // $153 current in amps (extended set)
419+
# define DEFAULT_A_HOLD_CURRENT 0.4 // $153 current in amps (extended set)
420420
#endif
421421
#ifndef DEFAULT_B_HOLD_CURRENT
422-
# define DEFAULT_B_HOLD_CURRENT 0.125 // $154 current in amps (extended set)
422+
# define DEFAULT_B_HOLD_CURRENT 0.4 // $154 current in amps (extended set)
423423
#endif
424424
#ifndef DEFAULT_C_HOLD_CURRENT
425-
# define DEFAULT_C_HOLD_CURRENT 0.125 // $154 current in amps (extended set)
425+
# define DEFAULT_C_HOLD_CURRENT 0.4 // $154 current in amps (extended set)
426426
#endif
427427

428428
// ========== Microsteps (SPI Drivers ) ================

Diff for: Grbl_Esp32/src/GCode.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -1483,8 +1483,10 @@ Error gc_execute_line(char* line, uint8_t client) {
14831483
// and absolute and incremental modes.
14841484
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
14851485
if (axis_command != AxisCommand::None) {
1486+
limitsCheckSoft(gc_block.values.xyz);
14861487
cartesian_to_motors(gc_block.values.xyz, pl_data, gc_state.position);
14871488
}
1489+
limitsCheckSoft(coord_data);
14881490
cartesian_to_motors(coord_data, pl_data, gc_state.position);
14891491
memcpy(gc_state.position, coord_data, sizeof(gc_state.position));
14901492
break;
@@ -1513,9 +1515,11 @@ Error gc_execute_line(char* line, uint8_t client) {
15131515
if (axis_command == AxisCommand::MotionMode) {
15141516
GCUpdatePos gc_update_pos = GCUpdatePos::Target;
15151517
if (gc_state.modal.motion == Motion::Linear) {
1518+
limitsCheckSoft(gc_block.values.xyz);
15161519
cartesian_to_motors(gc_block.values.xyz, pl_data, gc_state.position);
15171520
} else if (gc_state.modal.motion == Motion::Seek) {
15181521
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
1522+
limitsCheckSoft(gc_block.values.xyz);
15191523
cartesian_to_motors(gc_block.values.xyz, pl_data, gc_state.position);
15201524
} else if ((gc_state.modal.motion == Motion::CwArc) || (gc_state.modal.motion == Motion::CcwArc)) {
15211525
mc_arc(gc_block.values.xyz,

Diff for: Grbl_Esp32/src/Grbl.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222

2323
// Grbl versioning system
2424
const char* const GRBL_VERSION = "1.3a";
25-
const char* const GRBL_VERSION_BUILD = "20210816";
25+
const char* const GRBL_VERSION_BUILD = "20211016";
2626

2727
//#include <sdkconfig.h>
2828
#include <Arduino.h>

Diff for: Grbl_Esp32/src/Limits.cpp

+9
Original file line numberDiff line numberDiff line change
@@ -416,3 +416,12 @@ bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
416416
bool __attribute__((weak)) user_defined_homing(uint8_t cycle_mask) {
417417
return false;
418418
}
419+
420+
void limitsCheckSoft(float* target) {
421+
if (soft_limits->get()) {
422+
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
423+
if (sys.state != State::Jog && sys.state != State::Homing) {
424+
limits_soft_check(target);
425+
}
426+
}
427+
}

Diff for: Grbl_Esp32/src/Limits.h

+2
Original file line numberDiff line numberDiff line change
@@ -57,3 +57,5 @@ bool limitsCheckTravel(float* target);
5757

5858
// check if a switch has been defined
5959
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index);
60+
61+
void limitsCheckSoft(float* target);

Diff for: Grbl_Esp32/src/Machine.h

+1-2
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,7 @@
88
// !!! For initial testing, start with test_drive.h which disables
99
// all I/O pins
1010
// #include "Machines/atari_1020.h"
11-
# include "Machines/test_drive.h"
12-
11+
# include "Machines/6_pack_TMC2130_XYZ_Test.h"
1312
// !!! For actual use, change the line above to select a board
1413
// from Machines/, for example:
1514
// #include "Machines/3axis_v4.h"

Diff for: Grbl_Esp32/src/Machines/TMC2209_4x.h

+6-6
Original file line numberDiff line numberDiff line change
@@ -75,12 +75,12 @@
7575
#define STEPPERS_DISABLE_PIN GPIO_NUM_25
7676

7777

78-
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-5V-Buffered-Output-Module
79-
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/Quad-MOSFET-Module
80-
#define USER_DIGITAL_PIN_0 GPIO_NUM_4 // M62 M63
81-
#define USER_DIGITAL_PIN_1 GPIO_NUM_13 // M62 M63
82-
#define USER_DIGITAL_PIN_2 GPIO_NUM_17 // M62 M63
83-
#define USER_DIGITAL_PIN_3 GPIO_NUM_12 // M62 M63
78+
// Built in I/O
79+
#define SPINDLE_TYPE SpindleType::PWM
80+
#define SPINDLE_OUTPUT_PIN GPIO_NUM_4
81+
#define SPINDLE_ENABLE_PIN GPIO_NUM_13
82+
#define COOLANT_MIST_PIN GPIO_NUM_17 // M7 on M9 Off
83+
#define COOLANT_FLOOD_PIN GPIO_NUM_12 // M8 on M9 off
8484

8585

8686
// ===================== defaults ======================

Diff for: Grbl_Esp32/src/MotionControl.cpp

+4-8
Original file line numberDiff line numberDiff line change
@@ -45,14 +45,7 @@ bool mc_line(float* target, plan_line_data_t* pl_data) {
4545
bool submitted_result = false;
4646
// store the plan data so it can be cancelled by the protocol system if needed
4747
sys_pl_data_inflight = pl_data;
48-
// If enabled, check for soft limit violations. Placed here all line motions are picked up
49-
// from everywhere in Grbl.
50-
if (soft_limits->get()) {
51-
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
52-
if (sys.state != State::Jog) {
53-
limits_soft_check(target);
54-
}
55-
}
48+
5649
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
5750
if (sys.state == State::CheckMode) {
5851
sys_pl_data_inflight = NULL;
@@ -222,6 +215,7 @@ void mc_arc(float* target,
222215
position[axis_1] = center_axis1 + r_axis1;
223216
position[axis_linear] += linear_per_segment;
224217
pl_data->feed_rate = original_feedrate; // This restores the feedrate kinematics may have altered
218+
limitsCheckSoft(position);
225219
cartesian_to_motors(position, pl_data, previous_position);
226220
previous_position[axis_0] = position[axis_0];
227221
previous_position[axis_1] = position[axis_1];
@@ -233,6 +227,7 @@ void mc_arc(float* target,
233227
}
234228
}
235229
// Ensure last segment arrives at target location.
230+
limitsCheckSoft(target);
236231
cartesian_to_motors(target, pl_data, previous_position);
237232
}
238233

@@ -419,6 +414,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
419414
}
420415
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
421416
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Found");
417+
limitsCheckSoft(target);
422418
cartesian_to_motors(target, pl_data, gc_state.position);
423419
// Activate the probing state monitor in the stepper module.
424420
sys_probe_state = Probe::Active;

Diff for: Grbl_Esp32/src/Motors/TrinamicDriver.cpp

+83-39
Original file line numberDiff line numberDiff line change
@@ -54,9 +54,9 @@ namespace Motors {
5454
_spi_index(spi_index) {
5555
_has_errors = false;
5656
if (_driver_part_number == 2130) {
57-
tmcstepper = new TMC2130Stepper(_cs_pin, _r_sense, _spi_index);
57+
tmc2130 = new TMC2130Stepper(_cs_pin, _r_sense, _spi_index);
5858
} else if (_driver_part_number == 5160) {
59-
tmcstepper = new TMC5160Stepper(_cs_pin, _r_sense, _spi_index);
59+
tmc5160 = new TMC5160Stepper(_cs_pin, _r_sense, _spi_index);
6060
} else {
6161
grbl_msg_sendf(CLIENT_SERIAL,
6262
MsgLevel::Info,
@@ -67,14 +67,14 @@ namespace Motors {
6767
return;
6868
}
6969

70-
_has_errors = false;
70+
_has_errors = false;
7171

7272
digitalWrite(_cs_pin, HIGH);
7373
pinMode(_cs_pin, OUTPUT);
7474

7575
// use slower speed if I2S
7676
if (_cs_pin >= I2S_OUT_PIN_BASE) {
77-
tmcstepper->setSPISpeed(TRINAMIC_SPI_FREQ);
77+
(tmc2130) ? tmc2130->setSPISpeed(TRINAMIC_SPI_FREQ) : tmc5160->setSPISpeed(TRINAMIC_SPI_FREQ);
7878
}
7979

8080
link = List;
@@ -98,7 +98,7 @@ namespace Motors {
9898

9999
SPI.begin(); // this will get called for each motor, but does not seem to hurt anything
100100

101-
tmcstepper->begin();
101+
(tmc2130) ? tmc2130->begin() : tmc5160->begin();
102102

103103
_has_errors = !test(); // Try communicating with motor. Prints an error if there is a problem.
104104

@@ -142,7 +142,10 @@ namespace Motors {
142142
if (_has_errors) {
143143
return false;
144144
}
145-
switch (tmcstepper->test_connection()) {
145+
146+
uint8_t result = tmc2130 ? tmc2130->test_connection() : tmc5160->test_connection();
147+
148+
switch (result) {
146149
case 1:
147150
grbl_msg_sendf(CLIENT_SERIAL,
148151
MsgLevel::Info,
@@ -159,7 +162,8 @@ namespace Motors {
159162
// driver responded, so check for other errors from the DRV_STATUS register
160163

161164
TMC2130_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
162-
status.sr = tmcstepper->DRV_STATUS();
165+
166+
status.sr = tmc2130 ? tmc2130->DRV_STATUS() : tmc5160->DRV_STATUS();
163167

164168
bool err = false;
165169

@@ -208,8 +212,13 @@ namespace Motors {
208212
if (hold_i_percent > 1.0)
209213
hold_i_percent = 1.0;
210214
}
211-
tmcstepper->microsteps(axis_settings[_axis_index]->microsteps->get());
212-
tmcstepper->rms_current(run_i_ma, hold_i_percent);
215+
if (tmc2130) {
216+
tmc2130->microsteps(axis_settings[_axis_index]->microsteps->get());
217+
tmc2130->rms_current(run_i_ma, hold_i_percent);
218+
} else {
219+
tmc5160->microsteps(axis_settings[_axis_index]->microsteps->get());
220+
tmc5160->rms_current(run_i_ma, hold_i_percent);
221+
}
213222

214223
init_step_dir_pins();
215224
}
@@ -236,33 +245,65 @@ namespace Motors {
236245
}
237246
_mode = newMode;
238247

239-
switch (_mode) {
240-
case TrinamicMode ::StealthChop:
241-
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop");
242-
tmcstepper->en_pwm_mode(true);
243-
tmcstepper->pwm_autoscale(true);
244-
tmcstepper->diag1_stall(false);
245-
break;
246-
case TrinamicMode ::CoolStep:
247-
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep");
248-
tmcstepper->en_pwm_mode(false);
249-
tmcstepper->pwm_autoscale(false);
250-
tmcstepper->TCOOLTHRS(NORMAL_TCOOLTHRS); // when to turn on coolstep
251-
tmcstepper->THIGH(NORMAL_THIGH);
252-
break;
253-
case TrinamicMode ::StallGuard:
254-
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
255-
tmcstepper->en_pwm_mode(false);
256-
tmcstepper->pwm_autoscale(false);
257-
tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
258-
tmcstepper->THIGH(calc_tstep(homing_feed_rate->get(), 60.0));
259-
tmcstepper->sfilt(1);
260-
tmcstepper->diag1_stall(true); // stallguard i/o is on diag1
261-
tmcstepper->sgt(constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63));
262-
break;
263-
default:
264-
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "TRINAMIC_MODE_UNDEFINED");
248+
if (tmc2130) {
249+
switch (_mode) {
250+
case TrinamicMode ::StealthChop:
251+
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop");
252+
tmc2130->en_pwm_mode(true);
253+
tmc2130->pwm_autoscale(true);
254+
tmc2130->diag1_stall(false);
255+
break;
256+
case TrinamicMode ::CoolStep:
257+
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep");
258+
tmc2130->en_pwm_mode(false);
259+
tmc2130->pwm_autoscale(false);
260+
tmc2130->TCOOLTHRS(NORMAL_TCOOLTHRS); // when to turn on coolstep
261+
tmc2130->THIGH(NORMAL_THIGH);
262+
break;
263+
case TrinamicMode ::StallGuard:
264+
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
265+
tmc2130->en_pwm_mode(false);
266+
tmc2130->pwm_autoscale(false);
267+
tmc2130->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
268+
tmc2130->THIGH(calc_tstep(homing_feed_rate->get(), 60.0));
269+
tmc2130->sfilt(1);
270+
tmc2130->diag1_stall(true); // stallguard i/o is on diag1
271+
tmc2130->sgt(constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63));
272+
break;
273+
default:
274+
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "TRINAMIC_MODE_UNDEFINED");
275+
}
276+
} else {
277+
switch (_mode) {
278+
case TrinamicMode ::StealthChop:
279+
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop");
280+
tmc5160->en_pwm_mode(true);
281+
tmc5160->pwm_autoscale(true);
282+
tmc5160->diag1_stall(false);
283+
break;
284+
case TrinamicMode ::CoolStep:
285+
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep");
286+
tmc5160->en_pwm_mode(false);
287+
tmc5160->pwm_autoscale(false);
288+
tmc5160->TCOOLTHRS(NORMAL_TCOOLTHRS); // when to turn on coolstep
289+
tmc5160->THIGH(NORMAL_THIGH);
290+
break;
291+
case TrinamicMode ::StallGuard:
292+
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
293+
tmc5160->en_pwm_mode(false);
294+
tmc5160->pwm_autoscale(false);
295+
tmc5160->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
296+
tmc5160->THIGH(calc_tstep(homing_feed_rate->get(), 60.0));
297+
tmc5160->sfilt(1);
298+
tmc5160->diag1_stall(true); // stallguard i/o is on diag1
299+
tmc5160->sgt(constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63));
300+
break;
301+
default:
302+
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "TRINAMIC_MODE_UNDEFINED");
303+
}
265304
}
305+
306+
266307
}
267308

268309
/*
@@ -272,24 +313,27 @@ namespace Motors {
272313
if (_has_errors) {
273314
return;
274315
}
275-
uint32_t tstep = tmcstepper->TSTEP();
316+
uint32_t tstep = (tmc2130) ? tmc2130->TSTEP() : tmc5160->TSTEP();
276317

277318
if (tstep == 0xFFFFF || tstep < 1) { // if axis is not moving return
278319
return;
279320
}
280321
float feedrate = st_get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
281322

323+
int32_t st = (tmc2130) ? tmc2130->stallguard() : tmc5160->stallguard();
324+
int32_t sg = (tmc2130) ? tmc2130->sg_result() : tmc5160->sg_result();
325+
282326
grbl_msg_sendf(CLIENT_SERIAL,
283327
MsgLevel::Info,
284328
"%s Stallguard %d SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
285329
reportAxisNameMsg(_axis_index, _dual_axis_index),
286-
tmcstepper->stallguard(),
287-
tmcstepper->sg_result(),
330+
st,
331+
sg,
288332
feedrate,
289333
constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63));
290334

291335
TMC2130_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
292-
status.sr = tmcstepper->DRV_STATUS();
336+
status.sr = (tmc2130) ? tmc2130->DRV_STATUS() : tmc5160->DRV_STATUS();
293337

294338
// these only report if there is a fault condition
295339
report_open_load(status);

Diff for: Grbl_Esp32/src/Motors/TrinamicDriver.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,9 @@ namespace Motors {
100100
private:
101101
uint32_t calc_tstep(float speed, float percent);
102102

103-
TMC2130Stepper* tmcstepper; // all other driver types are subclasses of this one
103+
TMC2130Stepper* tmc2130 = nullptr;
104+
TMC2130Stepper* tmc5160 = nullptr;
105+
104106
TrinamicMode _homing_mode;
105107
uint8_t _cs_pin = UNDEFINED_PIN; // The chip select pin (can be the same for daisy chain)
106108
uint16_t _driver_part_number; // example: use 2130 for TMC2130

0 commit comments

Comments
 (0)