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

Move CoreXY out of main Grbl (#653)

* Created branch

* WIP

* Update parallel_delta.cpp

* Wip

* WIP

* Wip

* Still working on kinematics

- Added an interface into the jogging section

* WIP

* WIP

* wip

* WIP

* WIP

* Wip

* WIP

* WIP

* Wip

* Update machine defs

* Created branch

* WIP

* Update parallel_delta.cpp

* Wip

* WIP

* Wip

* Still working on kinematics

- Added an interface into the jogging section

* WIP

* WIP

* wip

* WIP

* WIP

* Wip

* WIP

* WIP

* Wip

* Update machine defs

* Machine def change. Moved switches to module 1

* WIP

* Cleanup before P.R.

- Fixed ranges for delta geometry
- Added post homing delay option for servos
- renamed and removed old machine defs.

* Fixing initialization problem when not in USE_KINEMATICS mode

* Fixing Git Mess

* Publishing Branch

- Not ready yet. Issues with Z axis
- Need to add midTbot option

* WIP

- Seems to be fully functional now.
- Need to add midTbot option.

* Update CoreXY.cpp

* I think it is ready for PR

- fixed $RST=#
- added midTbot geometry factor

* Fine tune midtbot definition

* Removed more unneeded corexy code.

* Fixed doubled #define in machine def file.

* Update after review comments
This commit is contained in:
bdring
2020-10-28 09:21:06 -05:00
committed by GitHub
parent 44c61a35e5
commit 13f6b37031
31 changed files with 991 additions and 266 deletions

View File

@@ -0,0 +1,307 @@
/*
CoreXY.cpp -
Copyright (c) 2020 Barton Dring @buildlog
https://corexy.com/theory.html
Limitations
- Must home via $H. $HX type homes not allowed
- Must home one axis per cycle
- limited to 3 axis systems...easy fix in increase (just donate)
============================================================================
Grbl 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/>.
FYI: http://forums.trossenrobotics.com/tutorials/introduction-129/delta-robot-kinematics-3276/
Better: http://hypertriangle.com/~alex/delta-robot-tutorial/
*/
#include "../src/Settings.h"
// Homing axis search distance multiplier. Computed by this value times the cycle travel.
#ifndef HOMING_AXIS_SEARCH_SCALAR
# define HOMING_AXIS_SEARCH_SCALAR 1.1 // Must be > 1 to ensure limit switch will be engaged.
#endif
#ifndef HOMING_AXIS_LOCATE_SCALAR
# define HOMING_AXIS_LOCATE_SCALAR 2.0 // Must be > 1 to ensure limit switch is cleared.
#endif
// The midTbot has a quirk where the x motor has to move twice as far as it would
// on a normal T-Bot or CoreXY
#ifndef MIDTBOT
const float geometry_factor = 1.0;
#else
const float geometry_factor = 2.0;
#endif
static float last_motors[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
static float last_cartesian[MAX_N_AXIS] = {};
// prototypes for helper functions
float three_axis_dist(float* point1, float* point2);
void machine_init() {
// print a startup message to show the kinematics are enable
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY Kinematics Init");
}
// This will always return true to prevent the normal Grbl homing cycle
bool user_defined_homing(uint8_t cycle_mask) {
uint8_t n_cycle; // each home is a multi cycle operation approach, pulloff, approach.....
float target[MAX_N_AXIS] = { 0.0 }; // The target for each move in the cycle
float max_travel;
uint8_t axis;
// check for single axis homing
if (cycle_mask != 0) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY Single axis homing not allowed. Use $H only");
return true;
}
// check for multi axis homing per cycle ($Homing/Cycle0=XY type)...not allowed in CoreXY
bool setting_error = false;
for (int cycle = 0; cycle < 3; cycle++) {
if (numberOfSetBits(homing_cycle[cycle]->get()) > 1) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"CoreXY Multi axis homing cycles not allowed. $Homing/Cycle%d=%s",
cycle,
homing_cycle[cycle]->getStringValue());
setting_error = true;
}
}
if (setting_error)
return true;
// setup the motion parameters
plan_line_data_t plan_data;
plan_line_data_t* pl_data = &plan_data;
memset(pl_data, 0, sizeof(plan_line_data_t));
pl_data->motion = {};
pl_data->motion.systemMotion = 1;
pl_data->motion.noFeedOverride = 1;
for (int cycle = 0; cycle < 3; cycle++) {
AxisMask mask = homing_cycle[cycle]->get();
mask = motors_set_homing_mode(mask, true); // non standard homing motors will do their own thing and get removed from the mask
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) {
if (bit(axis) == mask) {
// setup for the homing of this axis
bool approach = true;
float homing_rate = homing_seek_rate->get();
max_travel = HOMING_AXIS_SEARCH_SCALAR * axis_settings[axis]->max_travel->get();
sys.homing_axis_lock = 0xFF; // we don't need to lock any motors in CoreXY
n_cycle = (2 * NHomingLocateCycle + 1); // approach + ((pulloff + approach) * Cycles)
do {
bool switch_touched = false;
// zero all X&Y posiitons before each cycle
for (int idx = X_AXIS; idx <= Y_AXIS; idx++) {
sys_position[idx] = 0.0;
target[idx] = 0.0;
}
if (bit_istrue(homing_dir_mask->get(), bit(axis))) {
approach ? target[axis] = -max_travel : target[axis] = max_travel;
} else {
approach ? target[axis] = max_travel : target[axis] = -max_travel;
}
target[Z_AXIS] = system_convert_axis_steps_to_mpos(sys_position, Z_AXIS);
// convert back to motor steps
inverse_kinematics(target);
pl_data->feed_rate = homing_rate; // feed or seek rates
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
sys.step_control = {};
sys.step_control.executeSysMotion = true; // Set to execute homing motion and clear existing flags.
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
st_wake_up(); // Initiate motion
do {
if (approach) {
switch_touched = bitnum_istrue(limits_get_state(), axis);
}
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
// Exit routines: No time to run protocol_execute_realtime() in this loop.
if (sys_rt_exec_state.bit.safetyDoor || sys_rt_exec_state.bit.reset || cycle_stop) {
ExecState rt_exec_state;
rt_exec_state.value = sys_rt_exec_state.value;
// Homing failure condition: Reset issued during cycle.
if (rt_exec_state.bit.reset) {
sys_rt_exec_alarm = ExecAlarm::HomingFailReset;
}
// Homing failure condition: Safety door was opened.
if (rt_exec_state.bit.safetyDoor) {
sys_rt_exec_alarm = ExecAlarm::HomingFailDoor;
}
// Homing failure condition: Limit switch still engaged after pull-off motion
if (!approach && (limits_get_state() & cycle_mask)) {
sys_rt_exec_alarm = ExecAlarm::HomingFailPulloff;
}
// Homing failure condition: Limit switch not found during approach.
if (approach && cycle_stop) {
sys_rt_exec_alarm = ExecAlarm::HomingFailApproach;
}
if (sys_rt_exec_alarm != ExecAlarm::None) {
motors_set_homing_mode(cycle_mask, false); // tell motors homing is done...failed
mc_reset(); // Stop motors, if they are running.
protocol_execute_realtime();
return true;
} else {
// Pull-off motion complete. Disable CYCLE_STOP from executing.
cycle_stop = false;
break;
}
}
} while (!switch_touched);
#ifdef USE_I2S_STEPS
if (current_stepper == ST_I2S_STREAM) {
if (!approach) {
delay_ms(I2S_OUT_DELAY_MS);
}
}
#endif
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(homing_debounce->get()); // Delay to allow transient dynamics to dissipate.
approach = !approach;
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
if (approach) {
max_travel = homing_pulloff->get() * HOMING_AXIS_LOCATE_SCALAR;
homing_rate = homing_feed_rate->get();
} else {
max_travel = homing_pulloff->get();
homing_rate = homing_seek_rate->get();
}
} while (n_cycle-- > 0);
}
}
}
// after sussefully setting X & Y axes, we set the current positions
// set the cartesian axis position
for (axis = X_AXIS; axis <= Y_AXIS; axis++) {
if (bitnum_istrue(homing_dir_mask->get(), axis)) {
target[axis] = limitsMinPosition(axis) + homing_pulloff->get();
} else {
target[axis] = limitsMaxPosition(axis) - homing_pulloff->get();
}
}
last_cartesian[X_AXIS] = target[X_AXIS];
last_cartesian[Y_AXIS] = target[Y_AXIS];
last_cartesian[Z_AXIS] = system_convert_axis_steps_to_mpos(sys_position, Z_AXIS);
// convert to motors
inverse_kinematics(target);
// convert to steps
for (axis = X_AXIS; axis <= Y_AXIS; axis++) {
sys_position[axis] = target[axis] * axis_settings[axis]->steps_per_mm->get();
}
sys.step_control = {}; // Return step control to normal operation.
gc_sync_position();
plan_sync_position();
kinematics_post_homing();
limits_init();
return true;
}
// This function is used by Grbl convert Cartesian to motors
// this does not do any motion control
void inverse_kinematics(float* position) {
float motors[3];
motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];
motors[Z_AXIS] = position[Z_AXIS];
position[0] = motors[0];
position[1] = motors[1];
position[2] = motors[2];
}
// Inverse Kinematics calculates motor positions from real world cartesian positions
// position is the current position
// Breaking into segments is not needed with CoreXY, because it is a linear system.
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 motors[MAX_N_AXIS];
float feed_rate = pl_data->feed_rate; // save original feed rate
// calculate cartesian move distance for each axis
dx = target[X_AXIS] - position[X_AXIS];
dy = target[Y_AXIS] - position[Y_AXIS];
dz = target[Z_AXIS] - position[Z_AXIS];
float dist = sqrt((dx * dx) + (dy * dy) + (dz * dz));
motors[X_AXIS] = geometry_factor * target[X_AXIS] + target[Y_AXIS];
motors[Y_AXIS] = geometry_factor * target[X_AXIS] - target[Y_AXIS];
motors[Z_AXIS] = target[Z_AXIS];
float motor_distance = three_axis_dist(motors, last_motors);
if (!pl_data->motion.rapidMotion) {
pl_data->feed_rate *= (motor_distance / dist);
}
memcpy(last_motors, motors, sizeof(motors));
mc_line(motors, pl_data);
}
// motors -> cartesian
void forward_kinematics(float* position) {
float calc_fwd[MAX_N_AXIS];
// https://corexy.com/theory.html
calc_fwd[X_AXIS] = 0.5 / geometry_factor * (position[X_AXIS] + position[Y_AXIS]);
calc_fwd[Y_AXIS] = 0.5 * (position[X_AXIS] - position[Y_AXIS]);
position[X_AXIS] = calc_fwd[X_AXIS];
position[Y_AXIS] = calc_fwd[Y_AXIS];
}
bool kinematics_pre_homing(uint8_t cycle_mask) {
return false;
}
void kinematics_post_homing() {
gc_state.position[X_AXIS] = last_cartesian[X_AXIS];
gc_state.position[Y_AXIS] = last_cartesian[Y_AXIS];
gc_state.position[Z_AXIS] = last_cartesian[Z_AXIS];
}
// 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) {
return true;
}
void user_m30() {}
// ================ Local Helper functions =================
// 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])));
}

View File

@@ -90,7 +90,7 @@ void solenoidSyncTask(void* pvParameters) {
// continue with regular homing after setup
// return true if this completes homing
bool user_defined_homing() {
bool user_defined_homing(uint8_t cycle_mask) {
// create and start a task to do the special homing
homing_phase = HOMING_PHASE_FULL_APPROACH;
atari_homing = true;

View File

@@ -56,13 +56,13 @@ void machine_init() {}
#ifdef USE_CUSTOM_HOMING
/*
user_defined_homing() is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing() returns false, the rest of normal Grbl_ESP32
user_defined_homing(uint8_t cycle_mask) is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing(uint8_t cycle_mask) returns false, the rest of normal Grbl_ESP32
homing is skipped if it returns false, other normal homing continues. For
example, if you need to manually prep the machine for homing, you could implement
user_defined_homing() to wait for some button to be pressed, then return true.
user_defined_homing(uint8_t cycle_mask) to wait for some button to be pressed, then return true.
*/
bool user_defined_homing() {
bool user_defined_homing(uint8_t cycle_mask) {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}

View File

@@ -82,13 +82,13 @@ void machine_init() {
#ifdef USE_CUSTOM_HOMING
/*
user_defined_homing() is called at the begining of the normal Grbl_ESP32 homing
(user_defined_homing) is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing() returns false, the rest of normal Grbl_ESP32
homing is skipped if it returns false, other normal homing continues. For
example, if you need to manually prep the machine for homing, you could implement
user_defined_homing() to wait for some button to be pressed, then return true.
*/
bool user_defined_homing() {
bool user_defined_homing(uint8_t cycle_mask) {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}

View File

@@ -6,6 +6,9 @@
Jason Huggins, Tapster Robotics
Kinematics for a parallel delta robot.
Note: You must do a clean before compiling whenever this file is altered!
==================== How it Works ====================================
@@ -24,16 +27,17 @@
The arm 0 values (angle) are the arms at horizontal.
Positive angles are below horizontal.
The machine's Z zero point in the kinematics is parallel to the arm axes.
Delta_z_offset is the offset to the end effector joints at arm angle zero.
The is calculated at startup and used in the forward kinematics
The offset of the Z distance from the arm axes to the end effector joints
at arm angle zero will be printed at startup on the serial port.
Feedrate in gcode is in the cartesian uints. This must be converted to the
Feedrate in gcode is in the cartesian units. This must be converted to the
angles. This is done by calculating the segment move distance and the angle
move distance and applying that ration to the feedrate.
TODO Cleanup
Update so extra axes get delt with ... passed through properly
Have MPos use kinematics too
============================================================================
Grbl is free software: you can redistribute it and/or modify
@@ -50,13 +54,23 @@
Better: http://hypertriangle.com/~alex/delta-robot-tutorial/
*/
#include "../src/Settings.h"
enum class KinematicError : uint8_t {
NONE = 0,
OUT_OF_RANGE = 1,
ANGLE_TOO_NEGATIVE = 2,
ANGLE_TOO_POSITIVE = 3,
};
// trigonometric constants to speed calculations
// Create custom run time $ settings
FloatSetting* kinematic_segment_len;
FloatSetting* delta_crank_len;
FloatSetting* delta_link_len;
FloatSetting* delta_crank_side_len;
FloatSetting* delta_effector_side_len;
// trigonometric constants to speed up calculations
const float sqrt3 = 1.732050807;
const float dtr = M_PI / (float)180.0; // degrees to radians
const float sin120 = sqrt3 / 2.0;
@@ -66,60 +80,98 @@ const float sin30 = 0.5;
const float tan30 = 1.0 / sqrt3;
// the geometry of the delta
const float rf = RADIUS_FIXED; // radius of the fixed side (length of motor cranks)
const float re = RADIUS_EFF; // radius of end effector side (length of linkages)
const float f = LENGTH_FIXED_SIDE; // sized of fixed side triangel
const float e = LENGTH_EFF_SIDE; // size of end effector side triangle
float rf; // radius of the fixed side (length of motor cranks)
float re; // radius of end effector side (length of linkages)
float f; // sized of fixed side triangel
float e; // size of end effector side triangle
static float last_angle[N_AXIS] = { 0.0, 0.0, 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
float delta_z_offset; // Z offset of the effector from the arm centers
static float last_angle[3] = { 0.0, 0.0, 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
static float last_cartesian[N_AXIS] = {
0.0, 0.0, 0.0
}; // A place to save the previous motor angles for distance/feed rate calcs // Z offset of the effector from the arm centers
// prototypes for helper functions
int calc_forward_kinematics(float* angles, float* cartesian);
KinematicError delta_calcInverse(float* cartesian, float* angles);
KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta);
float three_axis_dist(float* point1, float* point2);
void read_settings();
void machine_init() {
// Calculate the Z offset at the motor zero angles ...
// Z offset is the z distance from the motor axes to the end effector axes at zero angle
float angles[N_AXIS] = { 0.0, 0.0, 0.0 };
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, 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();
// Calculate the Z offset at the arm zero angles ...
// Z offset is the z distance from the motor axes to the end effector axes at zero angle
calc_forward_kinematics(angles, cartesian); // Sets the cartesian values
// print a startup message to show the kinematics are enabled. Print the offset for reference
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Delta Kinematics Init: %s Z Offset:%4.3f", MACHINE_NAME, cartesian[Z_AXIS]);
// print a startup message to show the kinematics are enables
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Delata Kinematics Init: %s Z Offset:%4.3f", MACHINE_NAME, cartesian[Z_AXIS]);
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Delta Angle Range %3.3f, %3.3f", MAX_NEGATIVE_ANGLE, MAX_POSITIVE_ANGLE);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "DXL_COUNT_MIN %4.0f CENTER %d MAX %4.0f PER_RAD %d",
// DXL_COUNT_MIN,
// 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(uint8_t cycle_mask) { // 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) {
float motor_angles[3];
read_settings();
delta_calcInverse(position, motor_angles);
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
{
float dx, dy, dz; // distances in each cartesian axis
float motor_angles[N_AXIS];
float motor_angles[3];
float seg_target[N_AXIS]; // The target of the current segment
float feed_rate = pl_data->feed_rate; // save original feed rate
bool start_position_erorr = false;
bool show_error = true; // shows error once
float seg_target[3]; // The target of the current segment
float feed_rate = pl_data->feed_rate; // save original feed rate
bool show_error = true; // shows error once
// see if start is in work area...if not skip segments and try to go to target
KinematicError status = delta_calcInverse(position, motor_angles);
KinematicError status;
read_settings();
// grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Start %3.3f %3.3f %3.3f", position[0], position[1], position[2]);
// grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Target %3.3f %3.3f %3.3f", target[0], target[1], target[2]);
status = delta_calcInverse(position, motor_angles);
if (status == KinematicError::OUT_OF_RANGE) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Start position error");
start_position_erorr = true;
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Start position error %3.3f %3.3f %3.3f", position[0], position[1], position[2]);
//start_position_error = true;
}
// Check the destination to see if it is in work area
status = delta_calcInverse(target, motor_angles);
if (status == KinematicError::OUT_OF_RANGE) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Target unreachable");
return;
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Target unreachable error %3.3f %3.3f %3.3f", target[0], target[1], target[2]);
}
position[X_AXIS] += gc_state.coord_offset[X_AXIS];
@@ -127,14 +179,13 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
position[Z_AXIS] += gc_state.coord_offset[Z_AXIS];
// calculate cartesian move distance for each axis
dx = target[X_AXIS] - position[X_AXIS];
dy = target[Y_AXIS] - position[Y_AXIS];
dz = target[Z_AXIS] - position[Z_AXIS];
float dist = sqrt((dx * dx) + (dy * dy) + (dz * dz));
// determine the number of segments we need ... round up so there is at least 1 (except when dist is 0)
uint32_t segment_count = ceil(dist / SEGMENT_LENGTH);
uint32_t segment_count = ceil(dist / kinematic_segment_len->get());
float segment_dist = dist / ((float)segment_count); // distance of each segment...will be used for feedrate conversion
@@ -163,19 +214,46 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
} else {
if (show_error) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"Error:%d, Angs X:%4.3f Y:%4.3f Z:%4.3f]\r\n\r\n",
status,
motor_angles[0],
motor_angles[1],
motor_angles[2]);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "Error:%d, Angs X:%4.3f Y:%4.3f Z:%4.3f",
// status,
// motor_angles[0],
// motor_angles[1],
// motor_angles[2]);
show_error = false;
}
}
}
}
// 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();
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin Soft Check %3.3f, %3.3f, %3.3f", target[0], target[1], target[2]);
KinematicError status = delta_calcInverse(target, motor_angles);
switch (status) {
case KinematicError::OUT_OF_RANGE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target out of range");
break;
case KinematicError::ANGLE_TOO_NEGATIVE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target max negative");
break;
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);
}
// inverse kinematics: cartesian -> angles
// returned status: 0=OK, -1=non-existing position
KinematicError delta_calcInverse(float* cartesian, float* angles) {
@@ -271,6 +349,10 @@ KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta) {
return KinematicError::ANGLE_TOO_NEGATIVE;
}
if (theta > MAX_POSITIVE_ANGLE) {
return KinematicError::ANGLE_TOO_POSITIVE;
}
return KinematicError::NONE;
}
@@ -284,12 +366,17 @@ void forward_kinematics(float* position) {
float calc_fwd[N_AXIS];
int status;
read_settings();
// convert the system position in steps to radians
float position_radians[N_AXIS];
int32_t position_steps[N_AXIS]; // Copy current state of the system position variable
memcpy(position_steps, sys_position, sizeof(sys_position));
system_convert_array_steps_to_mpos(position_radians, position_steps);
// grbl_msg_sendf(
// CLIENT_SERIAL, MsgLevel::Info, "Fwd Kin Angs %1.3f, %1.3f, %1.3f ", position_radians[0], position_radians[1], position_radians[2]);
// detmine the position of the end effector joint center.
status = calc_forward_kinematics(position_radians, calc_fwd);
@@ -303,10 +390,56 @@ void forward_kinematics(float* position) {
}
}
bool kinematics_pre_homing(uint8_t cycle_mask) {
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
last_angle[X_AXIS] = sys_position[X_AXIS] / axis_settings[X_AXIS]->steps_per_mm->get();
last_angle[Y_AXIS] = sys_position[Y_AXIS] / axis_settings[Y_AXIS]->steps_per_mm->get();
last_angle[Z_AXIS] = sys_position[Z_AXIS] / axis_settings[Z_AXIS]->steps_per_mm->get();
read_settings();
calc_forward_kinematics(last_angle, last_cartesian);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "kinematics_post_homing Angles: %3.3f, %3.3f, %3.3f",
// last_angle[X_AXIS],
// last_angle[Y_AXIS],
// last_angle[Z_AXIS]);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "kinematics_post_homing Cartesian: %3.3f, %3.3f, %3.3f",
// last_cartesian[X_AXIS],
// last_cartesian[Y_AXIS],
// last_cartesian[Z_AXIS]);
gc_state.position[X_AXIS] = last_cartesian[X_AXIS];
gc_state.position[Y_AXIS] = last_cartesian[Y_AXIS];
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() {}
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
}

View File

@@ -263,13 +263,6 @@ static const uint8_t NHomingLocateCycle = 1; // Integer (1-128)
const double SAFETY_DOOR_SPINDLE_DELAY = 4.0; // Float (seconds)
const double SAFETY_DOOR_COOLANT_DELAY = 1.0; // Float (seconds)
// Enable CoreXY kinematics. Use ONLY with CoreXY machines.
// NOTE: This configuration option alters the motion of the X and Y axes to principle of operation
// defined at (http://corexy.com/theory.html). Motors are assumed to positioned and wired exactly as
// described, if not, motions may move in strange directions. Grbl requires the CoreXY A and B motors
// have the same steps per mm internally.
// #define COREXY // Default disabled. Uncomment to enable.
// Inverts select limit pin states based on the following mask. This effects all limit pin functions,
// such as hard limits and homing. However, this is different from overall invert limits setting.
// This build option will invert only the limit pins defined here, and then the invert limits setting
@@ -539,7 +532,7 @@ const int DEBOUNCE_PERIOD = 32; // in milliseconds default 32 microseconds
// these commands may be undesirable. Simply comment the desired macro to disable it.
#define ENABLE_RESTORE_WIPE_ALL // '$RST=*' Default enabled. Comment to disable.
#define ENABLE_RESTORE_DEFAULT_SETTINGS // '$RST=$' Default enabled. Comment to disable.
#define ENABLE_RESTORE_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
#define ENABLE_RESTORE_CLEAR_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
// Additional settings have been added to the original set that you see with the $$ command
// Some senders may not be able to parse anything different from the original set

View File

@@ -340,6 +340,30 @@
# define DEFAULT_C_HOMING_MPOS 0.0
#endif
#ifndef DEFAULT_HOMING_CYCLE_0
# define DEFAULT_HOMING_CYCLE_0 bit(Z_AXIS)
#endif
#ifndef DEFAULT_HOMING_CYCLE_1
# define DEFAULT_HOMING_CYCLE_1 (bit(X_AXIS) | bit(Y_AXIS))
#endif
#ifndef DEFAULT_HOMING_CYCLE_2
# define DEFAULT_HOMING_CYCLE_2 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_3
# define DEFAULT_HOMING_CYCLE_3 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_4
# define DEFAULT_HOMING_CYCLE_4 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_5
# define DEFAULT_HOMING_CYCLE_5 0
#endif
// ========== Motor current (SPI Drivers ) =============
#ifndef DEFAULT_X_CURRENT
# define DEFAULT_X_CURRENT 0.25 // $140 current in amps (extended set)

View File

@@ -1473,9 +1473,9 @@ Error gc_execute_line(char* line, uint8_t client) {
// and absolute and incremental modes.
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
if (axis_command != AxisCommand::None) {
mc_line(gc_block.values.xyz, pl_data); // kinematics kinematics not used for homing righ now
mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
}
mc_line(coord_data, pl_data);
mc_line_kins(coord_data, pl_data, gc_state.position);
memcpy(gc_state.position, coord_data, sizeof(gc_state.position));
break;
case NonModal::SetHome0:

View File

@@ -23,7 +23,7 @@
// Grbl versioning system
const char* const GRBL_VERSION = "1.3a";
const char* const GRBL_VERSION_BUILD = "20201022";
const char* const GRBL_VERSION_BUILD = "20201027";
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -96,14 +96,17 @@ void run_once();
void machine_init();
// Called if USE_CUSTOM_HOMING is defined
bool user_defined_homing();
bool user_defined_homing(uint8_t cycle_mask);
// Called if USE_KINEMATICS is defined
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
bool kinematics_pre_homing(uint8_t cycle_mask);
void kinematics_post_homing();
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
bool kinematics_pre_homing(uint8_t cycle_mask);
void kinematics_post_homing();
uint8_t kinematic_limits_check(float* target);
// Called if USE_FWD_KINEMATICS is defined
void inverse_kinematics(float* position); // used to return a converted value
void forward_kinematics(float* position);
// Called if MACRO_BUTTON_0_PIN or MACRO_BUTTON_1_PIN or MACRO_BUTTON_2_PIN is defined

View File

@@ -37,8 +37,13 @@ Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
return Error::TravelExceeded;
}
}
// Valid jog command. Plan, set state, and execute.
// Valid jog command. Plan, set state, and execute.
#ifndef USE_KINEMATICS
mc_line(gc_block->values.xyz, pl_data);
#else // else use kinematics
inverse_kinematics(gc_block->values.xyz, pl_data, gc_state.position);
#endif
if (sys.state == State::Idle) {
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
sys.state = State::Jog;

View File

@@ -109,11 +109,6 @@ void limits_go_home(uint8_t cycle_mask) {
for (uint8_t idx = 0; idx < n_axis; idx++) {
// Initialize step pin masks
step_pin[idx] = bit(idx);
#ifdef COREXY
if ((idx == A_MOTOR) || (idx == B_MOTOR)) {
step_pin[idx] = (bit(X_AXIS) | bit(Y_AXIS));
}
#endif
if (bit_istrue(cycle_mask, bit(idx))) {
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
max_travel = MAX(max_travel, (HOMING_AXIS_SEARCH_SCALAR)*axis_settings[idx]->max_travel->get());
@@ -133,20 +128,7 @@ void limits_go_home(uint8_t cycle_mask) {
// Set target location for active axes and setup computation for homing rate.
if (bit_istrue(cycle_mask, bit(idx))) {
n_active_axis++;
#ifdef COREXY
if (idx == X_AXIS) {
int32_t axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
sys_position[A_MOTOR] = axis_position;
sys_position[B_MOTOR] = -axis_position;
} else if (idx == Y_AXIS) {
int32_t axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
sys_position[A_MOTOR] = sys_position[B_MOTOR] = axis_position;
} else {
sys_position[Z_AXIS] = 0;
}
#else
sys_position[idx] = 0;
#endif
// Set target direction based on cycle mask and homing cycle approach state.
// NOTE: This happens to compile smaller than any other implementation tried.
auto mask = homing_dir_mask->get();
@@ -183,15 +165,7 @@ void limits_go_home(uint8_t cycle_mask) {
for (uint8_t idx = 0; idx < n_axis; idx++) {
if (axislock & step_pin[idx]) {
if (limit_state & bit(idx)) {
#ifdef COREXY
if (idx == Z_AXIS) {
axislock &= ~(step_pin[Z_AXIS]);
} else {
axislock &= ~(step_pin[A_MOTOR] | step_pin[B_MOTOR]);
}
#else
axislock &= ~(step_pin[idx]);
#endif
}
}
}
@@ -272,33 +246,6 @@ void limits_go_home(uint8_t cycle_mask) {
} else {
sys_position[idx] = (mpos - pulloff) * steps;
}
#ifdef COREXY
if (idx == X_AXIS) {
int32_t off_axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
sys_position[A_MOTOR] = set_axis_position + off_axis_position;
sys_position[B_MOTOR] = set_axis_position - off_axis_position;
} else if (idx == Y_AXIS) {
int32_t off_axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
sys_position[A_MOTOR] = off_axis_position + set_axis_position;
sys_position[B_MOTOR] = off_axis_position - set_axis_position;
} else {
sys_position[idx] = set_axis_position;
}
#else
//sys_position[idx] = set_axis_position;
/*
float max_mpos, min_mpos;
if (bit_istrue(homing_dir_mask->get(), bit(idx))) {
min_mpos = mpos;
max_mpos = mpos + travel;
} else {
min_mpos = mpos - travel;
max_mpos = mpos;
}
*/
#endif
}
}
sys.step_control = {}; // Return step control to normal operation.
@@ -386,7 +333,7 @@ AxisMask limits_get_state() {
return pinMask;
}
// Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed,
// Performs a soft limit check. Called from mcline() only. Assumes the machine has been homed,
// the workspace volume is in all negative space, and the system is in normal operation.
// NOTE: Used by jogging to limit travel within soft-limit volume.
void limits_soft_check(float* target) {

View File

@@ -124,4 +124,3 @@ Socket #5
#define DEFAULT_X_STEPS_PER_MM 800
#define DEFAULT_Y_STEPS_PER_MM 800
#define DEFAULT_Z_STEPS_PER_MM 800

View File

@@ -25,7 +25,15 @@
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
*/
#define MACHINE_NAME "MIDTBOT"
#define MACHINE_NAME "midTbot"
#define CUSTOM_CODE_FILENAME "../Custom/CoreXY.cpp"
#define MIDTBOT // applies the geometry correction to the kinematics
#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
#define USE_CUSTOM_HOMING
#define SPINDLE_TYPE SpindleType::NONE
@@ -35,10 +43,6 @@
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#ifndef COREXY // maybe set in config.h
#define COREXY
#endif
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define X_LIMIT_PIN GPIO_NUM_2
@@ -51,8 +55,11 @@
#define SPINDLE_TYPE SpindleType::NONE
// defaults
#define DEFAULT_HOMING_CYCLE_0 bit(Y_AXIS)
#define DEFAULT_HOMING_CYCLE_1 bit(X_AXIS)
#define DEFAULT_HOMING_CYCLE_0 bit(Z_AXIS)
#define DEFAULT_HOMING_CYCLE_1 bit(Y_AXIS)
#define DEFAULT_HOMING_CYCLE_2 bit(X_AXIS)
#define DEFAULT_HOMING_DIR_MASK (bit(X_AXIS) | bit (Z_AXIS)) // these home negative
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on
@@ -73,13 +80,12 @@
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_HOMING_ENABLE 1
#define DEFAULT_HOMING_DIR_MASK 1
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
#define DEFAULT_HOMING_FEED_RATE 500.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 3.0 // mm
#define DEFAULT_X_STEPS_PER_MM 200.0
#define DEFAULT_X_STEPS_PER_MM 100.0
#define DEFAULT_Y_STEPS_PER_MM 100.0
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode
@@ -93,4 +99,8 @@
#define DEFAULT_X_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode
#define DEFAULT_Z_MAX_TRAVEL 5.0 // This is percent in servo mode
#define DEFAULT_X_HOMING_MPOS DEFAULT_Z_MAX_TRAVEL // stays up after homing

View File

@@ -26,17 +26,24 @@
// ================= Firmware Customization ===================
#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
#define USE_FWD_KINEMATICS // report in cartesian
#define USE_MACHINE_INIT // There is some custom initialization for this machine
// ================== 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 SEGMENT_LENGTH 0.5 // segment length in mm
#define MAX_NEGATIVE_ANGLE -45 // in negative radians how far can the arms go up before damaging machine (max pi/2)
#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 =============
@@ -48,9 +55,17 @@
#define Y_DYNAMIXEL_ID 2 // protocol ID
#define Z_DYNAMIXEL_ID 3 // protocol ID
// limit servo to 180 degree motion
#define DXL_COUNT_MIN 1024
#define DXL_COUNT_MAX 3072
// limit servo to motion range
#define DXL_COUNTS 4096
#define DXL_COUNT_PER_RADIAN 652 // (DXL_COUNTS / 2.0 * M_PI)
#define DXL_CENTER 2015 // (DXL_COUNTS / 2) - (ARM_INTERNAL_ANGLE * DXL_COUNT_PER_RADIAN)
#undef DXL_COUNT_MIN
#define DXL_COUNT_MIN (DXL_CENTER + (MAX_NEGATIVE_ANGLE * DXL_COUNT_PER_RADIAN))
#undef DXL_COUNT_MAX
#define DXL_COUNT_MAX (DXL_CENTER + (MAX_POSITIVE_ANGLE * DXL_COUNT_PER_RADIAN))
#define SERVO_TIMER_INTERVAL 50
@@ -84,6 +99,11 @@
#define DEFAULT_HOMING_ENABLE 0
#define DEFAULT_HOMING_DIR_MASK 0
#define DEFAULT_HOMING_CYCLE_0 (bit(X_AXIS) | bit(Y_AXIS) | bit(Z_AXIS))
#define DEFAULT_X_HOMING_MPOS MAX_NEGATIVE_ANGLE
#define DEFAULT_Y_HOMING_MPOS DEFAULT_X_HOMING_MPOS
#define DEFAULT_Z_HOMING_MPOS DEFAULT_X_HOMING_MPOS
// the following must have the same values for each axis
#define DEFAULT_X_STEPS_PER_MM 800 // value is actually arbitrary, but keep it smallish
@@ -98,14 +118,5 @@
#define DEFAULT_Y_ACCELERATION DEFAULT_X_ACCELERATION // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION DEFAULT_X_ACCELERATION
#define DEFAULT_X_MAX_TRAVEL 3.14159265 // 180° in radians
#define DEFAULT_Y_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL //
#define DEFAULT_Z_MAX_TRAVEL DEFAULT_X_MAX_TRAVEL //
#define ARM_INTERNAL_ANGLE 2.866 // due to mounting angle
#define DEFAULT_X_HOMING_MPOS (DEFAULT_X_MAX_TRAVEL / 2.0)
#define DEFAULT_Y_HOMING_MPOS DEFAULT_X_HOMING_MPOS
#define DEFAULT_Z_HOMING_MPOS DEFAULT_X_HOMING_MPOS
#define SPINDLE_TYPE SpindleType::NONE

View File

@@ -0,0 +1,197 @@
#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 6P Trinamic"
#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
// 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 ======================
// Motor Socket #1
#define X_TRINAMIC_DRIVER 2130
#define X_DISABLE_PIN I2SO(0)
#define X_DIRECTION_PIN I2SO(1)
#define X_STEP_PIN I2SO(2)
#define X_CS_PIN I2SO(3)
#define X_RSENSE TMC2130_RSENSE_DEFAULT
// Motor Socket #2
#define Y_TRINAMIC_DRIVER X_TRINAMIC_DRIVER
#define Y_DIRECTION_PIN I2SO(4)
#define Y_STEP_PIN I2SO(5)
#define Y_DISABLE_PIN I2SO(7)
#define Y_CS_PIN I2SO(6)
#define Y_RSENSE X_RSENSE
// Motor Socket #3
#define Z_TRINAMIC_DRIVER X_TRINAMIC_DRIVER
#define Z_DISABLE_PIN I2SO(8)
#define Z_DIRECTION_PIN I2SO(9)
#define Z_STEP_PIN I2SO(10)
#define Z_CS_PIN I2SO(11)
#define Z_RSENSE X_RSENSE
// 6 Pack Pin Mapping
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/Socket-Pin-Number-Mapping
// // 4x Switch input module on CNC I/O module Socket #1
// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
#define X_LIMIT_PIN GPIO_NUM_33
#define Y_LIMIT_PIN GPIO_NUM_32
#define Z_LIMIT_PIN GPIO_NUM_35
// 4x Switch input module on CNC I/O module Socket #2
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
// #define X_LIMIT_PIN GPIO_NUM_2
// #define Y_LIMIT_PIN GPIO_NUM_25
// #define Z_LIMIT_PIN GPIO_NUM_39
// #define PROBE_PIN GPIO_NUM_36
//Example Quad MOSFET module on socket #3
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/Quad-MOSFET-Module
#define USER_DIGITAL_PIN_0 GPIO_NUM_26
#define USER_DIGITAL_PIN_1 GPIO_NUM_4
#define USER_DIGITAL_PIN_2 GPIO_NUM_16
#define USER_DIGITAL_PIN_3 GPIO_NUM_27
// Example Servo module in socket #4
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/RC-Servo-BESC-CNC-I-O-Module
// https://github.com/bdring/Grbl_Esp32/wiki/M62,-M63,-M64,-M65-&-M67-User-I-O-Commands
#define USER_ANALOG_PIN_0 GPIO_NUM_14
#define USER_ANALOG_PIN_1 GPIO_NUM_13
#define USER_ANALOG_PIN_2 GPIO_NUM_15
#define USER_ANALOG_PIN_3 GPIO_NUM_12
#define USER_ANALOG_PIN_0_FREQ 50 // for use with RC servos
#define USER_ANALOG_PIN_1_FREQ 50
#define USER_ANALOG_PIN_2_FREQ 50
#define USER_ANALOG_PIN_3_FREQ 50
// ================= defaults ===========================
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // keep them on, the trinamics will reduce power at idle
#define DEFAULT_X_MICROSTEPS 8
#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
#define DEFAULT_X_CURRENT 1.0
#define DEFAULT_X_HOLD_CURRENT 0.5
#define DEFAULT_Y_CURRENT 1.0
#define DEFAULT_Y_HOLD_CURRENT 0.5
#define DEFAULT_Z_CURRENT 1.0
#define DEFAULT_Z_HOLD_CURRENT 0.5
// 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
#define DEFAULT_HOMING_CYCLE_0 (bit(X_AXIS) | bit(Y_AXIS) | bit(Z_AXIS))
#define DEFAULT_HOMING_CYCLE_1 0 // override this one in defaults.h
// 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 DEFAULT_INVERT_PROBE_PIN 1
#define SPINDLE_TYPE SpindleType::NONE

View 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

View File

@@ -182,7 +182,7 @@
// functions. custom_code_template.cpp describes the functions
// that you can implement. The ifdef guards are described below:
//
// USE_CUSTOM_HOMING enables the user_defined_homing() function
// USE_CUSTOM_HOMING enables the user_defined_homing(uint8_t cycle_mask) function
// that can implement an arbitrary homing sequence.
// #define USE_CUSTOM_HOMING

View File

@@ -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

View File

@@ -115,8 +115,10 @@ void mc_arc(float* target,
float r_axis1 = -offset[axis_1];
float rt_axis0 = target[axis_0] - center_axis0;
float rt_axis1 = target[axis_1] - center_axis1;
float previous_position[MAX_N_AXIS] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
#ifdef USE_KINEMATICS
float previous_position[MAX_N_AXIS];
uint16_t n;
auto n_axis = number_axis->get();
for (n = 0; n < n_axis; n++) {
@@ -218,11 +220,7 @@ void mc_arc(float* target,
}
}
// Ensure last segment arrives at target location.
#ifdef USE_KINEMATICS
mc_line_kins(target, pl_data, previous_position);
#else
mc_line(target, pl_data);
#endif
}
// Execute dwell in seconds.
@@ -285,7 +283,7 @@ static bool axis_is_squared(uint8_t axis_mask) {
void mc_homing_cycle(uint8_t cycle_mask) {
bool no_cycles_defined = true;
#ifdef USE_CUSTOM_HOMING
if (user_defined_homing()) {
if (user_defined_homing(cycle_mask)) {
return;
}
#endif
@@ -352,7 +350,6 @@ void mc_homing_cycle(uint8_t cycle_mask) {
}
}
}
if (no_cycles_defined) {
report_status_message(Error::HomingNoCycles, CLIENT_ALL);
}
@@ -411,7 +408,8 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
return GCUpdatePos::None; // Nothing else to do but bail.
}
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
mc_line(target, pl_data);
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Found");
mc_line_kins(target, pl_data, gc_state.position);
// Activate the probing state monitor in the stepper module.
sys_probe_state = Probe::Active;
// Perform probing cycle. Wait here until probe is triggered or motion completes.

View File

@@ -87,8 +87,6 @@ namespace Motors {
// Homing justs sets the new system position and the servo will move there
bool RcServo::set_homing_mode(bool isHoming) {
float home_pos = 0.0;
sys_position[_axis_index] =
axis_settings[_axis_index]->home_mpos->get() * axis_settings[_axis_index]->steps_per_mm->get(); // convert to steps

View File

@@ -231,3 +231,9 @@ char* trim(char* str) {
end[1] = '\0';
return str;
}
// Returns the number of set number of set bits
// Would return 3 for 01100010
int numberOfSetBits(uint32_t i) {
return __builtin_popcount(i);
}

View File

@@ -53,11 +53,6 @@ static inline int toMotor2(int axis) {
return axis + MAX_AXES;
}
// CoreXY motor assignments. DO NOT ALTER.
// NOTE: If the A and B motor axis bindings are changed, this effects the CoreXY equations.
#define A_MOTOR X_AXIS // Must be X_AXIS
#define B_MOTOR Y_AXIS // Must be Y_AXIS
// Conversions
const double MM_PER_INCH = (25.40);
const double INCH_PER_MM = (0.0393701);
@@ -111,6 +106,8 @@ float constrain_float(float in, float min, float max);
bool char_is_numeric(char value);
char* trim(char* value);
int numberOfSetBits(uint32_t i);
template <class T>
void swap(T& a, T& b) {
T c(a);

View File

@@ -38,7 +38,7 @@ typedef struct {
// from g-code position for movements requiring multiple line motions,
// i.e. arcs, canned cycles, and backlash compensation.
float previous_unit_vec[MAX_N_AXIS]; // Unit vector of previous path line segment
float previous_nominal_speed; // Nominal speed of previous path line segment
float previous_nominal_speed; // Nominal speed of previous path line segment
} planner_t;
static planner_t pl;
@@ -313,49 +313,20 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
uint8_t idx;
// Copy position data based on type of motion being planned.
if (block->motion.systemMotion) {
#ifdef COREXY
position_steps[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
position_steps[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
position_steps[Z_AXIS] = sys_position[Z_AXIS];
#else
memcpy(position_steps, sys_position, sizeof(sys_position));
#endif
} else {
memcpy(position_steps, pl.position, sizeof(pl.position));
}
#ifdef COREXY
target_steps[A_MOTOR] = lround(target[A_MOTOR] * axis_settings[A_MOTOR]->steps_per_mm->get());
target_steps[B_MOTOR] = lround(target[B_MOTOR] * axis_settings[B_MOTOR]->steps_per_mm->get());
block->steps[A_MOTOR] = labs((target_steps[X_AXIS] - position_steps[X_AXIS]) + (target_steps[Y_AXIS] - position_steps[Y_AXIS]));
block->steps[B_MOTOR] = labs((target_steps[X_AXIS] - position_steps[X_AXIS]) - (target_steps[Y_AXIS] - position_steps[Y_AXIS]));
#endif
auto n_axis = number_axis->get();
for (idx = 0; idx < n_axis; idx++) {
// Calculate target position in absolute steps, number of steps for each axis, and determine max step events.
// Also, compute individual axes distance for move and prep unit vector calculations.
// NOTE: Computes true distance from converted step values.
#ifdef COREXY
if (!(idx == A_MOTOR) && !(idx == B_MOTOR)) {
target_steps[idx] = lround(target[idx] * axis_settings[idx]->steps_per_mm->get());
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
}
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
if (idx == A_MOTOR) {
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] + target_steps[Y_AXIS] - position_steps[Y_AXIS]) /
axis_settings[idx]->steps_per_mm->get();
} else if (idx == B_MOTOR) {
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] - target_steps[Y_AXIS] + position_steps[Y_AXIS]) /
axis_settings[idx]->steps_per_mm->get();
} else {
delta_mm = (target_steps[idx] - position_steps[idx]) / axis_settings[idx]->steps_per_mm->get();
}
#else
target_steps[idx] = lround(target[idx] * axis_settings[idx]->steps_per_mm->get());
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
delta_mm = (target_steps[idx] - position_steps[idx]) / axis_settings[idx]->steps_per_mm->get();
#endif
unit_vec[idx] = delta_mm; // Store unit vector numerator
unit_vec[idx] = delta_mm; // Store unit vector numerator
// Set direction bits. Bit enabled always means direction is negative.
if (delta_mm < 0.0) {
block->direction_bits |= bit(idx);
@@ -456,19 +427,9 @@ void plan_sync_position() {
// TODO: For motor configurations not in the same coordinate frame as the machine position,
// this function needs to be updated to accomodate the difference.
uint8_t idx;
auto n_axis = number_axis->get();
auto n_axis = number_axis->get();
for (idx = 0; idx < n_axis; idx++) {
#ifdef COREXY
if (idx == X_AXIS) {
pl.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
} else if (idx == Y_AXIS) {
pl.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
} else {
pl.position[idx] = sys_position[idx];
}
#else
pl.position[idx] = sys_position[idx];
#endif
pl.position[idx] = sys_position[idx];
}
}

View File

@@ -285,15 +285,15 @@ Error report_startup_lines(const char* value, WebUI::AuthenticationLevel auth_le
std::map<const char*, uint8_t, cmp_str> restoreCommands = {
#ifdef ENABLE_RESTORE_DEFAULT_SETTINGS
{ "$", SettingsRestore::Defaults }, { "settings", SettingsRestore::Defaults },
{ "$", SettingsRestore::Defaults }, { "settings", SettingsRestore::Defaults },
#endif
#ifdef ENABLE_RESTORE_CLEAR_PARAMETERS
{ "#", SettingsRestore::Parameters }, { "gcode", SettingsRestore::Parameters },
{ "#", SettingsRestore::Parameters }, { "gcode", SettingsRestore::Parameters },
#endif
#ifdef ENABLE_RESTORE_WIPE_ALL
{ "*", SettingsRestore::All }, { "all", SettingsRestore::All },
{ "*", SettingsRestore::All }, { "all", SettingsRestore::All },
#endif
{ "@", SettingsRestore::Wifi }, { "wifi", SettingsRestore::Wifi },
{ "@", SettingsRestore::Wifi }, { "wifi", SettingsRestore::Wifi },
};
Error restore_settings(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
if (!value) {
@@ -381,7 +381,7 @@ void make_grbl_commands() {
new GrblCommand("+", "ExtendedSettings/List", report_extended_settings, notCycleOrHold);
new GrblCommand("L", "GrblNames/List", list_grbl_names, notCycleOrHold);
new GrblCommand("S", "Settings/List", list_settings, notCycleOrHold);
new GrblCommand("SC","Settings/ListChanged", list_changed_settings, notCycleOrHold);
new GrblCommand("SC", "Settings/ListChanged", list_changed_settings, notCycleOrHold);
new GrblCommand("CMD", "Commands/List", list_commands, notCycleOrHold);
new GrblCommand("E", "ErrorCodes/List", listErrorCodes, anyState);
new GrblCommand("G", "GCode/Modes", report_gcode, anyState);

View File

@@ -519,9 +519,6 @@ void report_build_info(const char* line, uint8_t client) {
#ifdef COOLANT_MIST_PIN
grbl_send(client, "M"); // TODO Need to deal with M8...it could be disabled
#endif
#ifdef COREXY
grbl_send(client, "C");
#endif
#ifdef PARKING_ENABLE
grbl_send(client, "P");
#endif
@@ -941,7 +938,7 @@ char* reportAxisNameMsg(uint8_t axis) {
void reportTaskStackSize(UBaseType_t& saved) {
#ifdef DEBUG_REPORT_STACK_FREE
UBaseType_t newHighWater = uxTaskGetStackHighWaterMark(NULL);
UBaseType_t newHighWater = uxTaskGetStackHighWaterMark(NULL);
if (newHighWater != saved) {
saved = newHighWater;
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s Min Stack Space: %d", pcTaskGetTaskName(NULL), saved);

View File

@@ -233,7 +233,7 @@ const char* AxisMaskSetting::getCompatibleValue() {
}
static char* maskToString(uint32_t mask, char* strval) {
char* s = strval;
char* s = strval;
for (int i = 0; i < MAX_N_AXIS; i++) {
if (mask & bit(i)) {
*s++ = "XYZABC"[i];
@@ -566,7 +566,7 @@ void FlagSetting::setDefault() {
}
Error FlagSetting::setStringValue(char* s) {
s = trim(s);
s = trim(s);
Error err = check(s);
if (err != Error::Ok) {
return err;

View File

@@ -10,12 +10,12 @@ void settings_init();
// Define settings restore bitflags.
enum SettingsRestore {
Defaults = bit(0),
Parameters = bit(1),
Defaults = bit(0),
Parameters = bit(1),
StartupLines = bit(2),
// BuildInfo = bit(3), // Obsolete
Wifi = bit(4),
All = 0xff,
All = 0xff,
};
// Restore subsets of settings to default values
@@ -101,9 +101,9 @@ protected:
public:
static nvs_handle _handle;
static void init();
static Setting* List;
Setting* next() { return link; }
static void init();
static Setting* List;
Setting* next() { return link; }
Error check(char* s);
@@ -227,22 +227,25 @@ public:
class Coordinates {
private:
float _currentValue[MAX_N_AXIS];
float _currentValue[MAX_N_AXIS];
const char* _name;
public:
Coordinates(const char* name) : _name(name) {}
const char* getName() { return _name; }
bool load();
void setDefault() {
float zeros[MAX_N_AXIS] = { 0.0, };
bool load();
void setDefault() {
float zeros[MAX_N_AXIS] = {
0.0,
};
set(zeros);
};
// Copy the value to an array
void get(float* value) { memcpy(value, _currentValue, sizeof(_currentValue)); }
// Return a pointer to the array
const float* get() { return _currentValue; }
void set(float *value);
void set(float* value);
};
extern Coordinates* coords[CoordIndex::End];

View File

@@ -35,19 +35,19 @@ IntSetting* status_mask;
FloatSetting* junction_deviation;
FloatSetting* arc_tolerance;
FloatSetting* homing_feed_rate;
FloatSetting* homing_seek_rate;
FloatSetting* homing_debounce;
FloatSetting* homing_pulloff;
FloatSetting* homing_feed_rate;
FloatSetting* homing_seek_rate;
FloatSetting* homing_debounce;
FloatSetting* homing_pulloff;
AxisMaskSetting* homing_cycle[MAX_N_AXIS];
FloatSetting* spindle_pwm_freq;
FloatSetting* rpm_max;
FloatSetting* rpm_min;
FloatSetting* spindle_delay_spinup;
FloatSetting* spindle_delay_spindown;
FlagSetting* spindle_enbl_off_with_zero_speed;
FlagSetting* spindle_enable_invert;
FlagSetting* spindle_output_invert;
FloatSetting* spindle_pwm_freq;
FloatSetting* rpm_max;
FloatSetting* rpm_min;
FloatSetting* spindle_delay_spinup;
FloatSetting* spindle_delay_spindown;
FlagSetting* spindle_enbl_off_with_zero_speed;
FlagSetting* spindle_enable_invert;
FlagSetting* spindle_output_invert;
FloatSetting* spindle_pwm_off_value;
FloatSetting* spindle_pwm_min_value;

View File

@@ -166,17 +166,7 @@ void system_flag_wco_change() {
float system_convert_axis_steps_to_mpos(int32_t* steps, uint8_t idx) {
float pos;
float steps_per_mm = axis_settings[idx]->steps_per_mm->get();
#ifdef COREXY
if (idx == X_AXIS) {
pos = (float)system_convert_corexy_to_x_axis_steps(steps) / steps_per_mm;
} else if (idx == Y_AXIS) {
pos = (float)system_convert_corexy_to_y_axis_steps(steps) / steps_per_mm;
} else {
pos = steps[idx] / steps_per_mm;
}
#else
pos = steps[idx] / steps_per_mm;
#endif
pos = steps[idx] / steps_per_mm;
return pos;
}
@@ -275,15 +265,6 @@ void system_exec_control_pin(ControlPins pins) {
}
}
// CoreXY calculation only. Returns x or y-axis "steps" based on CoreXY motor steps.
int32_t system_convert_corexy_to_x_axis_steps(int32_t* steps) {
return (steps[A_MOTOR] + steps[B_MOTOR]) / 2;
}
int32_t system_convert_corexy_to_y_axis_steps(int32_t* steps) {
return (steps[A_MOTOR] - steps[B_MOTOR]) / 2;
}
// io_num is the virtual pin# and has nothing to do with the actual esp32 GPIO_NUM_xx
// It uses a mask so all can be turned of in ms_reset
bool sys_io_control(uint8_t io_num_mask, bool turnOn, bool synchronized) {

View File

@@ -213,9 +213,6 @@ float system_convert_axis_steps_to_mpos(int32_t* steps, uint8_t idx);
// Updates a machine 'position' array based on the 'step' array sent.
void system_convert_array_steps_to_mpos(float* position, int32_t* steps);
int32_t system_convert_corexy_to_x_axis_steps(int32_t* steps);
int32_t system_convert_corexy_to_y_axis_steps(int32_t* steps);
// A task that runs after a control switch interrupt for debouncing.
void controlCheckTask(void* pvParameters);
void system_exec_control_pin(ControlPins pins);

View File

@@ -31,6 +31,7 @@ build_flags =
;-DDEBUG_REPORT_HEAP_SIZE
;-DDEBUG_REPORT_STACK_FREE
[env]
lib_deps =
TMCStepper@>=0.7.0,<1.0.0