mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 19:02:35 +02:00
Merge branch 'tapster_pro' of https://github.com/bdring/Grbl_Esp32 into tapster_pro
This commit is contained in:
@@ -125,18 +125,17 @@ void machine_init() {
|
||||
// DXL_CENTER,
|
||||
// DXL_COUNT_MAX,
|
||||
// DXL_COUNT_PER_RADIAN);
|
||||
}
|
||||
|
||||
bool user_defined_homing() { // true = do not continue with normal Grbl homing
|
||||
bool user_defined_homing() { // true = do not continue with normal Grbl homing
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
return true;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
// This function is used by Grbl
|
||||
void inverse_kinematics(float* position) {
|
||||
// This function is used by Grbl
|
||||
void inverse_kinematics(float* position) {
|
||||
float motor_angles[3];
|
||||
|
||||
read_settings();
|
||||
@@ -144,11 +143,11 @@ void inverse_kinematics(float* position) {
|
||||
position[0] = motor_angles[0];
|
||||
position[1] = motor_angles[1];
|
||||
position[2] = motor_angles[2];
|
||||
}
|
||||
}
|
||||
|
||||
// This function is used by Grbl
|
||||
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
|
||||
{
|
||||
// This function is used by Grbl
|
||||
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
|
||||
{
|
||||
float dx, dy, dz; // distances in each cartesian axis
|
||||
float motor_angles[3];
|
||||
|
||||
@@ -226,10 +225,10 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
|
||||
uint8_t kinematic_limits_check(float* target) {
|
||||
// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
|
||||
uint8_t kinematic_limits_check(float* target) {
|
||||
float motor_angles[3];
|
||||
|
||||
read_settings();
|
||||
@@ -253,11 +252,11 @@ uint8_t kinematic_limits_check(float* target) {
|
||||
}
|
||||
|
||||
return (status == KinematicError::NONE);
|
||||
}
|
||||
}
|
||||
|
||||
// inverse kinematics: cartesian -> angles
|
||||
// returned status: 0=OK, -1=non-existing position
|
||||
KinematicError delta_calcInverse(float* cartesian, float* angles) {
|
||||
// inverse kinematics: cartesian -> angles
|
||||
// returned status: 0=OK, -1=non-existing position
|
||||
KinematicError delta_calcInverse(float* cartesian, float* angles) {
|
||||
angles[0] = angles[1] = angles[2] = 0;
|
||||
KinematicError status = KinematicError::NONE;
|
||||
|
||||
@@ -284,10 +283,10 @@ KinematicError delta_calcInverse(float* cartesian, float* angles) {
|
||||
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "xyx (%4.3f,%4.3f,%4.3f) ang (%4.3f,%4.3f,%4.3f)", x0, y0, z0, theta1, theta2, theta3);
|
||||
return status;
|
||||
}
|
||||
}
|
||||
|
||||
// inverse kinematics: angles -> cartesian
|
||||
int calc_forward_kinematics(float* angles, float* catesian) {
|
||||
// inverse kinematics: angles -> cartesian
|
||||
int calc_forward_kinematics(float* angles, float* catesian) {
|
||||
float t = (f - e) * tan30 / 2;
|
||||
|
||||
float y1 = -(t + rf * cos(angles[0]));
|
||||
@@ -329,9 +328,9 @@ int calc_forward_kinematics(float* angles, float* catesian) {
|
||||
catesian[X_AXIS] = (a1 * catesian[Z_AXIS] + b1) / dnm;
|
||||
catesian[Y_AXIS] = (a2 * catesian[Z_AXIS] + b2) / dnm;
|
||||
return 0;
|
||||
}
|
||||
// helper functions, calculates angle theta1 (for YZ-pane)
|
||||
KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta) {
|
||||
}
|
||||
// helper functions, calculates angle theta1 (for YZ-pane)
|
||||
KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta) {
|
||||
float y1 = -0.5 * 0.57735 * f; // f/2 * tg 30
|
||||
y0 -= 0.5 * 0.57735 * e; // shift center to edge
|
||||
// z = a + b*y
|
||||
@@ -355,15 +354,15 @@ KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta) {
|
||||
}
|
||||
|
||||
return KinematicError::NONE;
|
||||
}
|
||||
}
|
||||
|
||||
// Determine the unit distance between (2) 3D points
|
||||
float three_axis_dist(float* point1, float* point2) {
|
||||
// Determine the unit distance between (2) 3D points
|
||||
float three_axis_dist(float* point1, float* point2) {
|
||||
return sqrt(((point1[0] - point2[0]) * (point1[0] - point2[0])) + ((point1[1] - point2[1]) * (point1[1] - point2[1])) +
|
||||
((point1[2] - point2[2]) * (point1[2] - point2[2])));
|
||||
}
|
||||
// called by reporting for WPos status
|
||||
void forward_kinematics(float* position) {
|
||||
}
|
||||
// called by reporting for WPos status
|
||||
void forward_kinematics(float* position) {
|
||||
float calc_fwd[N_AXIS];
|
||||
int status;
|
||||
|
||||
@@ -389,18 +388,18 @@ void forward_kinematics(float* position) {
|
||||
} else {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "MSG:Fwd Kin Error");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask) { // true = do not continue with normal Grbl homing
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask) { // true = do not continue with normal Grbl homing
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
return true;
|
||||
#else
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "kinematics_pre_homing");
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void kinematics_post_homing() {
|
||||
void kinematics_post_homing() {
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
|
||||
#else
|
||||
@@ -434,13 +433,13 @@ void kinematics_post_homing() {
|
||||
#ifdef USE_POST_HOMING_DELAY
|
||||
delay(1000); // give time for servo type homing
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void user_m30() {}
|
||||
void user_m30() {}
|
||||
|
||||
void read_settings() {
|
||||
void read_settings() {
|
||||
rf = delta_crank_len->get(); // radius of the fixed side (length of motor cranks)
|
||||
re = delta_link_len->get(); // radius of end effector side (length of linkages)
|
||||
f = delta_crank_side_len->get(); // sized of fixed side triangel
|
||||
e = delta_effector_side_len->get(); // size of end effector side triangle
|
||||
}
|
||||
}
|
||||
|
@@ -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/test_drive.h"
|
||||
# include "Machines/tapster_pro_6P_trinamic.h"
|
||||
|
||||
// !!! For actual use, change the line above to select a board
|
||||
// from Machines/, for example:
|
||||
|
155
Grbl_Esp32/src/Machines/tapster_pro_stepstick.h
Normal file
155
Grbl_Esp32/src/Machines/tapster_pro_stepstick.h
Normal file
@@ -0,0 +1,155 @@
|
||||
#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
|
@@ -37,6 +37,8 @@
|
||||
|
||||
#define MACHINE_NAME "Test Drive - Demo Only No I/O!"
|
||||
|
||||
|
||||
#define N_AXIS 3
|
||||
// This cannot use homing because there are no switches
|
||||
#ifdef DEFAULT_HOMING_CYCLE_0
|
||||
#undef DEFAULT_HOMING_CYCLE_0
|
||||
|
@@ -52,7 +52,6 @@ void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position) {
|
||||
void mc_line(float* target, plan_line_data_t* pl_data) {
|
||||
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
||||
// from everywhere in Grbl.
|
||||
|
||||
if (soft_limits->get()) {
|
||||
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
|
||||
if (sys.state != State::Jog) {
|
||||
@@ -351,7 +350,6 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (no_cycles_defined) {
|
||||
report_status_message(Error::HomingNoCycles, CLIENT_ALL);
|
||||
}
|
||||
|
@@ -204,6 +204,17 @@ namespace Motors {
|
||||
return;
|
||||
}
|
||||
|
||||
float max_travel = axis_settings[_axis_index]->max_travel->get();
|
||||
float mpos = axis_settings[_axis_index]->home_mpos->get();
|
||||
|
||||
if (bit_istrue(homing_dir_mask->get(), bit(_axis_index))) {
|
||||
_position_min = mpos;
|
||||
_position_max = mpos + max_travel;
|
||||
} else {
|
||||
_position_min = mpos - max_travel;
|
||||
_position_max = mpos;
|
||||
}
|
||||
|
||||
uint16_t run_i_ma = (uint16_t)(axis_settings[_axis_index]->run_current->get() * 1000.0);
|
||||
float hold_i_percent;
|
||||
|
||||
|
@@ -27,10 +27,11 @@ build_flags =
|
||||
;-DMACHINE_FILENAME=test_drive.h ;Remove ";" from the beginning of this line and specify the machine file
|
||||
-DCORE_DEBUG_LEVEL=0
|
||||
-Wno-unused-variable
|
||||
-Wno-unused-function
|
||||
-Wno-unused-
|
||||
;-DDEBUG_REPORT_HEAP_SIZE
|
||||
;-DDEBUG_REPORT_STACK_FREE
|
||||
|
||||
|
||||
[env]
|
||||
lib_deps =
|
||||
TMCStepper@>=0.7.0,<1.0.0
|
||||
|
Reference in New Issue
Block a user