mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 19:32:39 +02:00
Cleanup before P.R.
- Fixed ranges for delta geometry - Added post homing delay option for servos - renamed and removed old machine defs.
This commit is contained in:
@@ -102,11 +102,11 @@ void machine_init() {
|
||||
float cartesian[N_AXIS] = { 0.0, 0.0, 0.0 };
|
||||
|
||||
// Custom $ settings
|
||||
kinematic_segment_len = new FloatSetting(EXTENDED, WG, NULL, "Kinematics/SegmentLength", KINEMATIC_SEGMENT_LENGTH, 0.2, 5.0);
|
||||
delta_crank_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/CrankLength", RADIUS_FIXED, 50, 150.0);
|
||||
delta_link_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/LinkLength", RADIUS_EFF, 0.2, 5.0);
|
||||
delta_crank_side_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/CrankSideLength", LENGTH_FIXED_SIDE, 0.2, 5.0);
|
||||
delta_effector_side_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/EffectorSideLength", LENGTH_EFF_SIDE, 0.2, 5.0);
|
||||
kinematic_segment_len = new FloatSetting(EXTENDED, WG, NULL, "Kinematics/SegmentLength", KINEMATIC_SEGMENT_LENGTH, 0.2, 1000.0);
|
||||
delta_crank_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/CrankLength", RADIUS_FIXED, 50.0, 500.0);
|
||||
delta_link_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/LinkLength", RADIUS_EFF, 50.0, 500.0);
|
||||
delta_crank_side_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/CrankSideLength", LENGTH_FIXED_SIDE, 20.0, 500.0);
|
||||
delta_effector_side_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/EffectorSideLength", LENGTH_EFF_SIDE, 20.0, 500.0);
|
||||
|
||||
read_settings();
|
||||
|
||||
@@ -248,6 +248,8 @@ uint8_t kinematic_limits_check(float* target) {
|
||||
case KinematicError::ANGLE_TOO_POSITIVE:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target max positive");
|
||||
break;
|
||||
case KinematicError::NONE:
|
||||
break;
|
||||
}
|
||||
|
||||
return (status == KinematicError::NONE);
|
||||
@@ -429,6 +431,9 @@ void kinematics_post_homing() {
|
||||
gc_state.position[Z_AXIS] = last_cartesian[Z_AXIS];
|
||||
|
||||
#endif
|
||||
#ifdef USE_POST_HOMING_DELAY
|
||||
delay(1000); // give time for servo type homing
|
||||
#endif
|
||||
}
|
||||
|
||||
void user_m30() {}
|
||||
|
@@ -8,7 +8,7 @@
|
||||
// !!! For initial testing, start with test_drive.h which disables
|
||||
// all I/O pins
|
||||
// #include "Machines/atari_1020.h"
|
||||
# include "Machines/tapster_pro_6P_trinamic.h"
|
||||
# include "Machines/tapster_3.h"
|
||||
|
||||
// !!! For actual use, change the line above to select a board
|
||||
// from Machines/, for example:
|
||||
|
@@ -31,20 +31,20 @@
|
||||
|
||||
// ================== Delta Geometry ===========================
|
||||
|
||||
#define RADIUS_FIXED 70.0; // radius of the fixed side (length of motor cranks)
|
||||
#define RADIUS_EFF 133.5; // radius of end effector side (length of linkages)
|
||||
#define LENGTH_FIXED_SIDE 179.437f; // sized of fixed side triangel
|
||||
#define LENGTH_EFF_SIDE 86.6025f; // size of end effector side triangle
|
||||
#define RADIUS_FIXED 70.0 // radius of the fixed side (length of motor cranks)
|
||||
#define RADIUS_EFF 133.5 // radius of end effector side (length of linkages)
|
||||
#define LENGTH_FIXED_SIDE 179.437f // sized of fixed side triangel
|
||||
#define LENGTH_EFF_SIDE 86.6025f // size of end effector side triangle
|
||||
#define KINEMATIC_SEGMENT_LENGTH 1.0f // segment length in mm
|
||||
#define MAX_NEGATIVE_ANGLE -(M_PI / 3.0) // 60 degrees up
|
||||
#define MAX_POSITIVE_ANGLE (M_PI / 2.0) // 90 degrees down
|
||||
#define ARM_INTERNAL_ANGLE 0.05 // radians 2.866° // due to mounting angle
|
||||
#define USE_POST_HOMING_DELAY // Servos need time to reach destination before idle kicks in
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL MAX_POSITIVE_ANGLE - MAX_NEGATIVE_ANGLE
|
||||
#define DEFAULT_Y_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL //
|
||||
#define DEFAULT_Z_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL //
|
||||
|
||||
|
||||
// =================== Machine Hardware Definition =============
|
||||
|
||||
#define DYNAMIXEL_TXD GPIO_NUM_4
|
@@ -1,155 +0,0 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
tapster_pro_stepstick.h
|
||||
|
||||
2020 - Bart Dring, Jason Huggins (Tapster Robotics)
|
||||
|
||||
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_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "Tapster Pro Delta (StepStick)"
|
||||
|
||||
#define CUSTOM_CODE_FILENAME "Custom/parallel_delta.cpp"
|
||||
/*
|
||||
// enable these special machine functions to be called from the main program
|
||||
#define USE_KINEMATICS // there are kinematic equations for this machine
|
||||
#define FWD_KINEMATICS_REPORTING // report in cartesian
|
||||
#define USE_RMT_STEPS // Use the RMT periferal to generate step pulses
|
||||
#define USE_TRINAMIC // some Trinamic motors are used on this machine
|
||||
#define USE_MACHINE_TRINAMIC_INIT // there is a machine specific setup for the drivers
|
||||
#define USE_MACHINE_INIT // There is some custom initialization for this machine
|
||||
|
||||
#define SEGMENT_LENGTH 0.5 // segment length in mm
|
||||
#define KIN_ANGLE_CALC_OK 0
|
||||
#define KIN_ANGLE_ERROR -1
|
||||
|
||||
#define MAX_NEGATIVE_ANGLE -36 // in degrees how far can the arms go up?
|
||||
|
||||
#define HOMING_CURRENT_REDUCTION 1.0
|
||||
|
||||
*/
|
||||
|
||||
#define N_AXIS 3
|
||||
|
||||
#define USE_KINEMATICS // there are kinematic equations for this machine
|
||||
#define USE_FWD_KINEMATICS // report in cartesian
|
||||
#define USE_MACHINE_INIT // There is some custom initialization for this machine
|
||||
|
||||
// ================== Delta Geometry ===========================
|
||||
|
||||
#define RADIUS_FIXED 100.0f // radius of the fixed side (length of motor cranks)
|
||||
#define RADIUS_EFF 220.0f // radius of end effector side (length of linkages)
|
||||
#define LENGTH_FIXED_SIDE 294.449f // sized of fixed side triangel
|
||||
#define LENGTH_EFF_SIDE 86.6025f // size of end effector side triangle
|
||||
#define KINEMATIC_SEGMENT_LENGTH 1.0f // segment length in mm
|
||||
#define MAX_NEGATIVE_ANGLE -0.75f //
|
||||
#define MAX_POSITIVE_ANGLE (M_PI / 2.0) //
|
||||
|
||||
|
||||
// ================== Config ======================
|
||||
|
||||
// Set $Homing/Cycle0=XYZ
|
||||
|
||||
// === Special Features
|
||||
|
||||
// I2S (steppers & other output-only pins)
|
||||
#define USE_I2S_OUT
|
||||
#define USE_I2S_STEPS
|
||||
//#define DEFAULT_STEPPER ST_I2S_STATIC
|
||||
// === Default settings
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
|
||||
|
||||
#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
|
||||
|
||||
#define I2S_OUT_BCK GPIO_NUM_22
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
// ================== CPU MAP ======================
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
// Motor Socket #3
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
|
||||
// CNC I/O Modules
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_33
|
||||
#define Y_LIMIT_PIN GPIO_NUM_32
|
||||
#define Z_LIMIT_PIN GPIO_NUM_35
|
||||
|
||||
// ================= defaults ===========================
|
||||
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // keep them on, the trinamics will reduce power at idle
|
||||
|
||||
#define DEFAULT_X_MICROSTEPS 32
|
||||
#define DEFAULT_Y_MICROSTEPS DEFAULT_X_MICROSTEPS
|
||||
#define DEFAULT_Z_MICROSTEPS DEFAULT_X_MICROSTEPS
|
||||
|
||||
// some math to figure out microsteps per unit // units could bedegrees or radians
|
||||
#define UNITS_PER_REV (2.0 * M_PI) // 360.0 degrees or 6.2831853 radians
|
||||
#define STEPS_PER_REV 400.0
|
||||
#define REDUCTION_RATIO (60.0 / 16.0) // the pulleys on arm and motor
|
||||
#define MICROSTEPS_PER_REV (STEPS_PER_REV * (float)DEFAULT_X_MICROSTEPS * REDUCTION_RATIO)
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM (MICROSTEPS_PER_REV / UNITS_PER_REV)
|
||||
#define DEFAULT_Y_STEPS_PER_MM DEFAULT_X_STEPS_PER_MM
|
||||
#define DEFAULT_Z_STEPS_PER_MM DEFAULT_X_STEPS_PER_MM
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 100.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE DEFAULT_X_MAX_RATE
|
||||
#define DEFAULT_Z_MAX_RATE DEFAULT_X_MAX_RATE
|
||||
|
||||
#define DEFAULT_X_ACCELERATION 20.0
|
||||
#define DEFAULT_Y_ACCELERATION DEFAULT_X_ACCELERATION
|
||||
#define DEFAULT_Z_ACCELERATION DEFAULT_X_ACCELERATION
|
||||
|
||||
// homing
|
||||
#define DEFAULT_HOMING_FEED_RATE 25
|
||||
#define DEFAULT_HOMING_SEEK_RATE 100
|
||||
#define DEFAULT_HOMING_DIR_MASK (bit(X_AXIS) | bit(Y_AXIS) | bit(Z_AXIS)) // all axes home negative
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 0
|
||||
|
||||
// The machine homes up and above center. MPos is the axis angle in radians
|
||||
// at the homing posiiton
|
||||
|
||||
#define DEFAULT_X_HOMING_MPOS -0.75 // neagtive because above horizontal
|
||||
#define DEFAULT_Y_HOMING_MPOS -0.75
|
||||
#define DEFAULT_Z_HOMING_MPOS -0.75
|
||||
|
||||
// the total travel is straight down from horizontal (pi/2) + the up travel
|
||||
#define DEFAULT_X_MAX_TRAVEL ((M_PI / 2.0) - DEFAULT_X_HOMING_MPOS)
|
||||
#define DEFAULT_Y_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL
|
||||
#define DEFAULT_Z_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL
|
||||
|
||||
#define DEFAULT_HOMING_PULLOFF -DEFAULT_X_HOMING_MPOS
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
Reference in New Issue
Block a user