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

Update Trinamic Libray, Support messages in Gcode comments

- Swapped out TMC2130 Library for TMCStepper library to cover more Trinamic drivers
- Updated CPU_MAP_TMC2130_PEN for new library
- Messages can now be embedded in gcode (MSG Now Hear This) per NIST gcode rules. Messages are currently sent to all CLIENTs
- Added a message to explian why you get an error when trying to probe without a defined probe pin
This commit is contained in:
bdring
2019-09-16 17:30:36 -05:00
parent 23de746a2a
commit 164489918d
13 changed files with 301 additions and 125 deletions

View File

@@ -1,58 +0,0 @@
/*
TMC2130.cpp - Support for TMC2130 Stepper Drivers SPI Mode
Part of Grbl_ESP32
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
GrblESP32 is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
#ifdef X_CS_PIN
TMC2130Stepper TMC2130_X = TMC2130Stepper(X_CS_PIN);
#endif
#ifdef Y_CS_PIN
TMC2130Stepper TMC2130_Y = TMC2130Stepper(Y_CS_PIN);
#endif
#ifdef Z_CS_PIN
TMC2130Stepper TMC2130_Z = TMC2130Stepper(Z_CS_PIN);
#endif
void TMC2130_Init()
{
#ifdef X_CS_PIN
TMC2130_X.begin(); // Initiate pins and registries
TMC2130_X.microsteps(32);
TMC2130_X.setCurrent(200, 0.11, 0.5);
TMC2130_X.stealthChop(1); // Enable extremely quiet stepping
#endif
#ifdef Y_CS_PIN
TMC2130_Y.begin(); // Initiate pins and registries
TMC2130_Y.microsteps(32);
TMC2130_Y.setCurrent(200, 0.11, 0.5);
TMC2130_Y.stealthChop(1); // Enable extremely quiet stepping
#endif
#ifdef Z_CS_PIN
TMC2130_Z.begin(); // Initiate pins and registries
TMC2130_Z.microsteps(32);
TMC2130_Z.setCurrent(200, 0.11, 0.5);
TMC2130_Z.stealthChop(1); // Enable extremely quiet stepping
#endif
}

View File

@@ -1,31 +0,0 @@
/*
TMC2130.h - Support for TMC2130 Stepper Drivers SPI Mode
Part of Grbl_ESP32
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
GrblESP32 is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef TMC2130_h
#define TMC2130_h
#include "grbl.h"
#include <TMC2130Stepper.h>
#ifdef USE_TMC2130
void TMC2130_Init();
#endif
#endif

View File

@@ -999,9 +999,6 @@
#undef IGNORE_CONTROL_PINS
#endif
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
@@ -1177,32 +1174,44 @@
#define USE_RMT_STEPS
#define USE_TMC2130 // make sure you assign chip select pins to each axis
#define USE_TRINAMIC // Using at least 1 trinamic driver
#define X_STEP_PIN GPIO_NUM_12
#define X_DIRECTION_PIN GPIO_NUM_26
#define X_CS_PIN GPIO_NUM_17 //chip select
#define X_RMT_CHANNEL 0
#define X_TRINAMIC // using SPI control
#define X_DRIVER_TMC2130 // Which Driver Type?
#define X_CS_PIN GPIO_NUM_17 //chip select
#define X_RSENSE 0.11f // .11 Ohm
#define X_MICROSTEPS 32
#define X_RMS_CURRENT 750 // run current in mA
#define X_HOLD_CURRENT 0.25 // hold current as percentage of run current
#define X_RMT_CHANNEL 0
#define Y_STEP_PIN GPIO_NUM_14
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_CS_PIN GPIO_NUM_16 //chip select
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_TRINAMIC // using SPI control
#define Y_DRIVER_TMC2130 // Which Driver Type?
#define Y_CS_PIN GPIO_NUM_16 //chip select
#define Y_RSENSE 0.11f // .11 Ohm
#define Y_MICROSTEPS 32
#define Y_RMS_CURRENT 750 // in mA
#define Y_HOLD_CURRENT 0.25 // hold current as percentage of run current
#define Y_RMT_CHANNEL 1
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#ifndef USE_SERVO_AXES // maybe set in config.h
#define USE_SERVO_AXES
#endif
#define SERVO_Z_PIN GPIO_NUM_27
#define SERVO_Z_PIN GPIO_NUM_27
#define SERVO_Z_CHANNEL_NUM 5
#define SERVO_Z_RANGE_MIN 0.0
#define SERVO_Z_RANGE_MAX 5.0
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
// *** the flood coolant feature code is activated by defining this pins
// *** Comment it out to use the pin for other features
@@ -1224,14 +1233,14 @@
#define SPINDLE_PWM_MAX_VALUE 255 // (2^SPINDLE_PWM_BIT_PRECISION)
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define X_LIMIT_PIN GPIO_NUM_2
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B11
#define X_LIMIT_PIN GPIO_NUM_2
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B11
#endif

View File

@@ -182,9 +182,14 @@ uint8_t gc_execute_line(char *line, uint8_t client)
case 1:
case 2:
case 3:
#ifdef PROBE_PIN //only allow G38 "Probe" commands if a probe pin is defined.
case 38:
#endif
#ifndef PROBE_PIN //only allow G38 "Probe" commands if a probe pin is defined.
if (int_value == 38) {
grbl_send(CLIENT_SERIAL, "[MSG:No probe pin defined!]\r\n");
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported G command]
}
#endif
// Check for G0/1/2/3/38 being called with G10/28/30/92 on same block.
// * G43.1 is also an axis command but is not explicitly defined this way.
if (axis_command) {

View File

@@ -20,7 +20,7 @@
// Grbl versioning system
#define GRBL_VERSION "1.1f"
#define GRBL_VERSION_BUILD "20190910"
#define GRBL_VERSION_BUILD "20190916"
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -85,7 +85,8 @@
#include "servo_axis.h"
#endif
#ifdef USE_TMC2130
#include "TMC2130.h" // https://github.com/teemuatlut/TMC2130Stepper
#ifdef USE_TRINAMIC
#include "grbl_trinamic.h"
//#include "TMCStepper.h" // https://github.com/teemuatlut/TMCStepper
#endif

View File

@@ -0,0 +1,190 @@
/*
grbl_trinamic.cpp - Support for Trinamic Stepper Drivers SPI Mode
using the TMCStepper library
Part of Grbl_ESP32
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
Grbl_ESP32 is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
// TODO try to use the #define ## method to clean this up
//#define DRIVER(driver, axis) driver##Stepper = TRINAMIC_axis## = driver##Stepper(axis##_CS_PIN, axis##_RSENSE);
#ifdef X_TRINAMIC
#ifdef X_DRIVER_TMC2130
TMC2130Stepper TRINAMIC_X = TMC2130Stepper(X_CS_PIN, X_RSENSE);
#endif
#ifdef X_DRIVER_TMC2208
TMC2208Stepper TRINAMIC_X = TMC2208Stepper(X_CS_PIN, X_RSENSE);
#endif
#ifdef X_DRIVER_TMC2209
TMC2209Stepper TRINAMIC_X = TMC2209Stepper(X_CS_PIN, X_RSENSE);
#endif
#ifdef X_DRIVER_TMC5160
TMC5160Stepper TRINAMIC_X = TMC5160Stepper(X_CS_PIN, X_RSENSE);
#endif
#endif
#ifdef Y_TRINAMIC
#ifdef Y_DRIVER_TMC2130
TMC2130Stepper TRINAMIC_Y = TMC2130Stepper(Y_CS_PIN, Y_RSENSE);
#endif
#ifdef Y_DRIVER_TMC2208
TMC2208Stepper TRINAMIC_Y = TMC2208Stepper(Y_CS_PIN, Y_RSENSE);
#endif
#ifdef Y_DRIVER_TMC2209
TMC2209Stepper TRINAMIC_Y = TMC2209Stepper(Y_CS_PIN, Y_RSENSE);
#endif
#ifdef Y_DRIVER_TMC5160
TMC5160Stepper TRINAMIC_Y = TMC5160Stepper(Y_CS_PIN, Y_RSENSE);
#endif
#endif
#ifdef Z_TRINAMIC
#ifdef Z_DRIVER_TMC2130
TMC2130Stepper TRINAMIC_Z = TMC2130Stepper(Z_CS_PIN, Z_RSENSE);
#endif
#ifdef Z_DRIVER_TMC2208
TMC2208Stepper TRINAMIC_Z = TMC2208Stepper(Z_CS_PIN, Z_RSENSE);
#endif
#ifdef Z_DRIVER_TMC2209
TMC2209Stepper TRINAMIC_Z = TMC2209Stepper(Z_CS_PIN, Z_RSENSE);
#endif
#ifdef Z_DRIVER_TMC5160
TMC5160Stepper TRINAMIC_Z = TMC5160Stepper(Z_CS_PIN, Z_RSENSE);
#endif
#endif
#ifdef A_TRINAMIC
#ifdef A_DRIVER_TMC2130
TMC2130Stepper TRINAMIC_A = TMC2130Stepper(A_CS_PIN, A_RSENSE);
#endif
#ifdef A_DRIVER_TMC2208
TMC2208Stepper TRINAMIC_A = TMC2208Stepper(A_CS_PIN, A_RSENSE);
#endif
#ifdef A_DRIVER_TMC2209
TMC2209Stepper TRINAMIC_A = TMC2209Stepper(A_CS_PIN, A_RSENSE);
#endif
#ifdef A_DRIVER_TMC5160
TMC5160Stepper TRINAMIC_A = TMC5160Stepper(A_CS_PIN, A_RSENSE);
#endif
#endif
#ifdef B_TRINAMIC
#ifdef B_DRIVER_TMC2130
TMC2130Stepper TRINAMIC_B = TMC2130Stepper(B_CS_PIN, B_RSENSE);
#endif
#ifdef B_DRIVER_TMC2208
TMC2208Stepper TRINAMIC_B = TMC2208Stepper(B_CS_PIN, B_RSENSE);
#endif
#ifdef B_DRIVER_TMC2209
TMC2209Stepper TRINAMIC_B = TMC2209Stepper(B_CS_PIN, B_RSENSE);
#endif
#ifdef B_DRIVER_TMC5160
TMC5160Stepper TRINAMIC_B = TMC5160Stepper(B_CS_PIN, B_RSENSE);
#endif
#endif
#ifdef C_TRINAMIC
#ifdef C_DRIVER_TMC2130
TMC2130Stepper TRINAMIC_c = TMC2130Stepper(C_CS_PIN, C_RSENSE);
#endif
#ifdef C_DRIVER_TMC2208
TMC2208Stepper TRINAMIC_C = TMC2208Stepper(C_CS_PIN, C_RSENSE);
#endif
#ifdef C_DRIVER_TMC2209
TMC2209Stepper TRINAMIC_C = TMC2209Stepper(C_CS_PIN, C_RSENSE);
#endif
#ifdef C_DRIVER_TMC5160
TMC5160Stepper TRINAMIC_C = TMC5160Stepper(C_CS_PIN, C_RSENSE);
#endif
#endif
// TODO ABC Axes
void Trinamic_Init()
{
grbl_send(CLIENT_SERIAL, "[MSG:Using TMCStepper Library]\r\n");
SPI.begin();
#ifdef X_TRINAMIC
TRINAMIC_X.begin(); // Initiate pins and registries
TRINAMIC_X.toff(5);
TRINAMIC_X.microsteps(X_MICROSTEPS);
#ifdef X_HOLD_CURRENT
TRINAMIC_X.rms_current(X_RMS_CURRENT, X_HOLD_CURRENT);
#else
TRINAMIC_X.rms_current(X_RMS_CURRENT); // default hold current is 0.5 or 50%
#endif
TRINAMIC_X.en_pwm_mode(1); // Enable extremely quiet stepping
TRINAMIC_X.pwm_autoscale(1);
#endif
#ifdef Y_TRINAMIC
TRINAMIC_Y.begin(); // Initiate pins and registries
TRINAMIC_Y.toff(5);
TRINAMIC_Y.microsteps(Y_MICROSTEPS);
#ifdef Y_HOLD_CURRENT
TRINAMIC_Y.rms_current(Y_RMS_CURRENT, Y_HOLD_CURRENT);
#else
TRINAMIC_Y.rms_current(Y_RMS_CURRENT); // default hold current is 0.5 or 50%
#endif
TRINAMIC_Y.en_pwm_mode(1); // Enable extremely quiet stepping
TRINAMIC_Y.pwm_autoscale(1);
#endif
#ifdef Z_TRINAMIC
TRINAMIC_Z.begin(); // Initiate pins and registries
TRINAMIC_Z.toff(5);
TRINAMIC_Z.microsteps(Z_MICROSTEPS);
TRINAMIC_Z.rms_current(Z_RMS_CURRENT);
TRINAMIC_Z.en_pwm_mode(1); // Enable extremely quiet stepping
TRINAMIC_Z.pwm_autoscale(1);
#endif
#ifdef A_TRINAMIC
TRINAMIC_A.begin(); // Initiate pins and registries
TRINAMIC_A.toff(5);
TRINAMIC_A.microsteps(A_MICROSTEPS);
TRINAMIC_A.rms_current(A_RMS_CURRENT);
TRINAMIC_A.en_pwm_mode(1); // Enable extremely quiet stepping
TRINAMIC_A.pwm_autoscale(1);
#endif
#ifdef B_TRINAMIC
TRINAMIC_B.begin(); // Initiate pins and registries
TRINAMIC_B.toff(5);
TRINAMIC_B.microsteps(B_MICROSTEPS);
TRINAMIC_B.rms_current(B_RMS_CURRENT);
TRINAMIC_B.en_pwm_mode(1); // Enable extremely quiet stepping
TRINAMIC_B.pwm_autoscale(1);
#endif
#ifdef C_TRINAMIC
TRINAMIC_C.begin(); // Initiate pins and registries
TRINAMIC_C.toff(5);
TRINAMIC_C.microsteps(C_MICROSTEPS);
TRINAMIC_C.rms_current(C_RMS_CURRENT);
TRINAMIC_C.en_pwm_mode(1); // Enable extremely quiet stepping
TRINAMIC_C.pwm_autoscale(1);
#endif
// TODO ABC Axes
}

View File

@@ -0,0 +1,31 @@
/*
grbl_trinamic.h - Support for TMC2130 Stepper Drivers SPI Mode
Part of Grbl_ESP32
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
GrblESP32 is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef GRBL_TRINAMIC_h
#define GRBL_TRINAMIC_h
#include "grbl.h"
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
#ifdef USE_TRINAMIC
void Trinamic_Init();
#endif
#endif

View File

@@ -35,6 +35,7 @@
static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
static char comment[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
static void protocol_exec_rt_suspend();
@@ -79,6 +80,7 @@ void protocol_main_loop()
uint8_t line_flags = 0;
uint8_t char_counter = 0;
uint8_t comment_char_counter = 0;
uint8_t c;
for (;;) {
@@ -149,7 +151,7 @@ void protocol_main_loop()
// Reset tracking data for next line.
line_flags = 0;
char_counter = 0;
comment_char_counter = 0;
} else {
if (line_flags) {
@@ -159,7 +161,14 @@ void protocol_main_loop()
// Throw away all (except EOL) comment characters and overflow characters.
if (c == ')') {
// End of '()' comment. Resume line allowed.
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); }
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) {
line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES);
comment[comment_char_counter] = 0; // null terminate
report_gcode_comment(comment);
}
}
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { // capture all characters into a comment buffer
comment[comment_char_counter++] = c;
}
} else {
if (c <= ' ') {
@@ -177,6 +186,7 @@ void protocol_main_loop()
// In the future, we could simply remove the items within the comments, but retain the
// comment control characters, so that the g-code parser can error-check it.
line_flags |= LINE_FLAG_COMMENT_PARENTHESES;
comment_char_counter = 0;
} else if (c == ';') {
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;

View File

@@ -267,10 +267,10 @@ void report_feedback_message(uint8_t message_code) // OK to send to all clients
// Welcome message
void report_init_message(uint8_t client)
{
grbl_send(client,"\r\nGrbl " GRBL_VERSION " ['$' for help]\r\n");
#ifdef CPU_MAP_NAME
grbl_send(client,"[MSG:Using cpu_map..." CPU_MAP_NAME "]\r\n");
#endif
grbl_send(client,"\r\nGrbl " GRBL_VERSION " ['$' for help]\r\n");
}
// Grbl help message
@@ -842,3 +842,19 @@ void report_realtime_steps()
grbl_sendf(CLIENT_ALL, "%ld\n", sys_position[idx]); // OK to send to all ... debug stuff
}
}
void report_gcode_comment(char *comment) {
char msg[80];
const uint8_t offset = 4; // ignore "MSG_" part of comment
uint8_t index = offset;
if (strstr(comment, "MSG")) {
while(index < strlen(comment)) {
msg[index-offset] = comment[index];
index++;
}
msg[index-offset] = 0; // null terminate
grbl_sendf(CLIENT_ALL, "[MSG:GCode Comment %s]\r\n",msg);
}
}

View File

@@ -155,6 +155,8 @@ void report_execute_startup_message(char *line, uint8_t status_code, uint8_t cli
// Prints build info and user info
void report_build_info(char *line, uint8_t client);
void report_gcode_comment(char *comment);
#ifdef DEBUG
void report_realtime_debug();
#endif

View File

@@ -44,6 +44,7 @@ uint8_t serial_get_rx_buffer_available(uint8_t client)
void serial_init()
{
Serial.begin(BAUD_RATE);
grbl_send(CLIENT_SERIAL,"\r\n"); // create some white space after ESP32 boot info
serialCheckTaskHandle = 0;
// create a task to check for incoming data
xTaskCreatePinnedToCore( serialCheckTask, // task

View File

@@ -52,7 +52,7 @@ void init_servos()
{
//grbl_send(CLIENT_SERIAL, "[MSG: Init Servos]\r\n");
#ifdef SERVO_X_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Init X Servo]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:X Servo]\r\n");
X_Servo_Axis.init();
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
@@ -60,12 +60,12 @@ void init_servos()
X_Servo_Axis.set_disable_with_steppers(false);
#endif
#ifdef SERVO_Y_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Init Y Servo]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:Y Servo]\r\n");
Y_Servo_Axis.init();
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
#endif
#ifdef SERVO_Z_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Init Z Servo]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:Z Servo]\r\n");
Z_Servo_Axis.init();
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
#ifdef SERVO_Z_HOMING_TYPE
@@ -80,7 +80,7 @@ void init_servos()
#endif
#ifdef SERVO_A_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Init A Servo]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:A Servo]\r\n");
A_Servo_Axis.init();
A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
A_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
@@ -88,12 +88,12 @@ void init_servos()
A_Servo_Axis.set_disable_with_steppers(false);
#endif
#ifdef SERVO_B_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Init B Servo]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:B Servo]\r\n");
B_Servo_Axis.init();
B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
#endif
#ifdef SERVO_C_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Init C Servo]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:C Servo]\r\n");
C_Servo_Axis.init();
C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
//C_Servo_Axis.set_homing_type(SERVO_HOMING_TARGET);

View File

@@ -433,21 +433,21 @@ void stepper_init()
set_stepper_disable(true);
#endif
#ifdef USE_TMC2130
TMC2130_Init();
#endif
//#ifdef USE_TMC2130
// TMC2130_Init();
//#endif
#ifdef USE_TRINAMIC
#ifdef USE_TRINAMIC
Trinamic_Init();
#endif
grbl_sendf(CLIENT_SERIAL, "[MSG:Axis count %d]\r\n", N_AXIS);
#ifdef USE_RMT_STEPS
grbl_send(CLIENT_SERIAL, "[MSG:Using RMT Steps]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:RMT Steps]\r\n");
initRMT();
#else
grbl_send(CLIENT_SERIAL, "[MSG:Using Timed Steps]\r\n");
grbl_send(CLIENT_SERIAL, "[MSG:Timed Steps]\r\n");
// make the step pins outputs
#ifdef X_STEP_PIN
pinMode(X_STEP_PIN, OUTPUT);