1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-08 05:10:53 +02:00

Merge pull request #230 from bdring/Devt

Devt
This commit is contained in:
bdring
2019-09-24 11:57:07 -05:00
committed by GitHub
16 changed files with 419 additions and 296 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

@@ -546,7 +546,7 @@
#ifdef CPU_MAP_POLAR_COASTER // The Buildlog.net pen polar coaster controller V1
#define CPU_MAP_NAME "CPU_MAP_POLAR_COASTER"
#define USE_KINEMATICS
#define USE_KINEMATICS
#define FWD_KINEMATICS_REPORTING // report in cartesian
#include "polar_coaster.h"
@@ -913,182 +913,114 @@
#endif
#ifdef CPU_MAP_MPCNC_V1P2
#ifdef CPU_MAP_MPCNC // all versions...select below
// This is the CPU Map for the Buildlog.net MPCNC controller
// uncomment ONE of the following versions
//#define V1P1
#define V1P2 // works for V1.2.1 as well
#ifdef V1P1
#define CPU_MAP_NAME "CPU_MAP_MPCNC_V1P1"
#else // V1P2
#define CPU_MAP_NAME "CPU_MAP_MPCNC_V1P2"
#endif
// switch to the correct default settings
#ifdef DEFAULTS_GENERIC
#undef DEFAULTS_GENERIC
#endif
#define DEFAULTS_MPCNC
// switch to the correct default settings
#ifdef DEFAULTS_GENERIC
#undef DEFAULTS_GENERIC
#endif
#define DEFAULTS_MPCNC
#define USE_GANGED_AXES // allow two motors on an axis
#define X_STEP_PIN GPIO_NUM_12
#define X_STEP_B_PIN GPIO_NUM_22 // ganged motor
#define X_AXIS_SQUARING
#define USE_GANGED_AXES // allow two motors on an axis
#define X_STEP_PIN GPIO_NUM_12
#define X_STEP_B_PIN GPIO_NUM_22 // ganged motor
#define X_AXIS_SQUARING
#define Y_STEP_PIN GPIO_NUM_14
#define Y_STEP_B_PIN GPIO_NUM_21 // ganged motor
#define Y_AXIS_SQUARING
#define Z_STEP_PIN GPIO_NUM_27
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Z_DIRECTION_PIN GPIO_NUM_33
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define Y_STEP_PIN GPIO_NUM_14
#define Y_STEP_B_PIN GPIO_NUM_21 // ganged motor
#define Y_AXIS_SQUARING
#define Z_STEP_PIN GPIO_NUM_27
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Z_DIRECTION_PIN GPIO_NUM_33
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
//#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
//#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
#ifdef V1P1
#define SPINDLE_PWM_PIN GPIO_NUM_17
#else // V1p2
#define SPINDLE_PWM_PIN GPIO_NUM_2
#else
#define SPINDLE_PWM_PIN GPIO_NUM_16
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
#define SPINDLE_PWM_CHANNEL 0
// PWM Generator is based on 80,000,000 Hz counter
// Therefor the freq determines the resolution
// 80,000,000 / freq = max resolution
// For 5000 that is 80,000,000 / 5000 = 16000
// round down to nearest bit count for SPINDLE_PWM_MAX_VALUE = 13bits (8192)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#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.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
// Relay can be used for Spindle or Coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
#define X_LIMIT_PIN GPIO_NUM_17
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
#endif
#else
#define SPINDLE_PWM_PIN GPIO_NUM_16
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
#define SPINDLE_PWM_CHANNEL 0
// PWM Generator is based on 80,000,000 Hz counter
// Therefor the freq determines the resolution
// 80,000,000 / freq = max resolution
// For 5000 that is 80,000,000 / 5000 = 16000
// round down to nearest bit count for SPINDLE_PWM_MAX_VALUE = 13bits (8192)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#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.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
// Relay can be used for spindle or either coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
//#define COOLANT_MIST_PIN GPIO_NUM_2
#ifdef V1P1 //v1p1
#define X_LIMIT_PIN GPIO_NUM_2
#else
#define X_LIMIT_PIN GPIO_NUM_17
#endif
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
#ifdef V1P2
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
#define ENABLE_SOFTWARE_DEBOUNCE
#endif
#define PROBE_PIN GPIO_NUM_35
// The default value in config.h is wrong for this controller
#ifdef INVERT_CONTROL_PIN_MASK
#undef INVERT_CONTROL_PIN_MASK
#endif
#define INVERT_CONTROL_PIN_MASK B1110
// Note: defualt is #define IGNORE_CONTROL_PINS in config.h
// uncomment to these lines to use them
#ifdef IGNORE_CONTROL_PINS
#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
#endif
#ifdef CPU_MAP_MPCNC_V1P1
// This is the CPU Map for the Buildlog.net MPCNC controller
#endif
#define CPU_MAP_NAME "CPU_MAP_MPCNC_V1P1"
#define PROBE_PIN GPIO_NUM_35
// switch to the correct default settings
#ifdef DEFAULTS_GENERIC
#undef DEFAULTS_GENERIC
#endif
#define DEFAULTS_MPCNC
// The default value in config.h is wrong for this controller
#ifdef INVERT_CONTROL_PIN_MASK
#undef INVERT_CONTROL_PIN_MASK
#endif
#define USE_GANGED_AXES // allow two motors on an axis
#define X_STEP_PIN GPIO_NUM_12
#define X_STEP_B_PIN GPIO_NUM_22 // ganged motor
#define X_AXIS_SQUARING
#define Y_STEP_PIN GPIO_NUM_14
#define Y_STEP_B_PIN GPIO_NUM_21 // ganged motor
#define Y_AXIS_SQUARING
#define Z_STEP_PIN GPIO_NUM_27
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Z_DIRECTION_PIN GPIO_NUM_33
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
// Note: if you use PWM rather than relay, you could map GPIO_NUM_17 to mist or flood
#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
#define SPINDLE_PWM_PIN GPIO_NUM_17
#else
#define SPINDLE_PWM_PIN GPIO_NUM_16
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
#define SPINDLE_PWM_CHANNEL 0
// PWM Generator is based on 80,000,000 Hz counter
// Therefor the freq determines the resolution
// 80,000,000 / freq = max resolution
// For 5000 that is 80,000,000 / 5000 = 16000
// round down to nearest bit count for SPINDLE_PWM_MAX_VALUE = 13bits (8192)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#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.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
// Relay can be used for Spindle or Coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_17
#define X_LIMIT_PIN GPIO_NUM_34
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
#define PROBE_PIN GPIO_NUM_35
// The default value in config.h is wrong for this controller
#ifdef INVERT_CONTROL_PIN_MASK
#undef INVERT_CONTROL_PIN_MASK
#endif
#define INVERT_CONTROL_PIN_MASK B1100
// Note: check the #define IGNORE_CONTROL_PINS is the way you want in config.h
//#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
#define INVERT_CONTROL_PIN_MASK B1110
// Note: default is #define IGNORE_CONTROL_PINS in config.h
// uncomment to these lines to use them
#ifdef IGNORE_CONTROL_PINS
#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
#endif
@@ -1177,32 +1109,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_TRINAMIC // using SPI control
#define X_DRIVER_TMC2130 // Which Driver Type?
#define X_CS_PIN GPIO_NUM_17 //chip select
#define X_RMT_CHANNEL 0
#define X_RSENSE 0.11f // .11 Ohm
#define X_MICROSTEPS 32
#define X_RMS_CURRENT 700 // 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 700 // 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 +1168,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 "20190924"
//#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,172 @@
/*
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_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_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_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_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_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_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

@@ -213,6 +213,14 @@ void mc_dwell(float seconds)
// executing the homing cycle. This prevents incorrect buffered plans after homing.
void mc_homing_cycle(uint8_t cycle_mask)
{
// This give kinematics a chance to do something before normal homing
// if it returns true, the homing is canceled.
#ifdef USE_KINEMATICS
if (!kinematics_homing(cycle_mask))
return;
#endif
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
// with machines with limits wired on both ends of travel to one limit pin.
// TODO: Move the pin-specific LIMIT_PIN call to limits.c as a function.

View File

@@ -53,6 +53,20 @@
#ifdef CPU_MAP_POLAR_COASTER
#ifdef USE_KINEMATICS
// this get called before homing
// return true to complete normal home
// return false to exit normal homing
bool kinematics_homing(uint8_t cycle_mask)
{
// cycle mask not used for polar coaster
// zero the axes that are not homed
sys_position[Y_AXIS] = 0.0f;
sys_position[Z_AXIS] = 0.0f;
return true; // finish normal homing cycle
}
/*
Apply inverse kinematics for a polar system
@@ -140,6 +154,8 @@ void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *positio
mc_line(polar, pl_data);
}
// TO DO don't need a feedrate for rapids
}
@@ -193,17 +209,24 @@ void calc_polar(float *target_xyz, float *polar, float last_angle)
{
float delta_ang; // the difference from the last and next angle
target_xyz[X_AXIS] *= -1.0; // compensate for Polar Coaster's radial axis being mirrored (right side) from normal 0deg
//grbl_sendf(CLIENT_SERIAL, "calc polar: x...%4.2f y...%4.2f\r\n", target_xyz[X_AXIS], target_xyz[Y_AXIS]);
// determine the new polar values
polar[POLAR_AXIS] = atan2(target_xyz[Y_AXIS], target_xyz[X_AXIS]) * 180.0 / M_PI;
//target_xyz[X_AXIS] *= -1.0; // compensate for Polar Coaster's radial axis being mirrored (right side) from normal 0deg
// no negative angles...we want the absolute angle not -90, use 270
if (polar[POLAR_AXIS] < 0.0) {
polar[POLAR_AXIS] = 360.0 + polar[POLAR_AXIS];
}
polar[RADIUS_AXIS] = hypot_f(target_xyz[X_AXIS], target_xyz[Y_AXIS]);
if (polar[RADIUS_AXIS] == 0) {
polar[POLAR_AXIS] = last_angle; // don't care about angle at center
}
else {
polar[POLAR_AXIS] = atan2(target_xyz[Y_AXIS], target_xyz[X_AXIS]) * 180.0 / M_PI;
// no negative angles...we want the absolute angle not -90, use 270
if (polar[POLAR_AXIS] < 0.0) {
polar[POLAR_AXIS] = 360.0 + polar[POLAR_AXIS];
}
}
polar[Z_AXIS] = target_xyz[Z_AXIS]; // Z is unchanged

View File

@@ -29,6 +29,7 @@
#include "grbl.h"
bool kinematics_homing(uint8_t cycle_mask);
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position);
void calc_polar(float *target_xyz, float *polar, float last_angle);
void user_defined_macro(uint8_t index);

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

@@ -274,11 +274,9 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
#endif
#ifdef VARIABLE_SPINDLE
#ifdef VARIABLE_SPINDLE
// Set real-time spindle output as segment is loaded, just prior to the first step.
if (st_prep_block->is_pwm_rate_adjusted) {
spindle_set_speed(st.exec_segment->spindle_pwm);
}
#endif
} else {
@@ -433,21 +431,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);