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

Merge branch 'tapster_pro' of https://github.com/bdring/Grbl_Esp32 into tapster_pro

This commit is contained in:
bdring
2020-10-23 15:08:00 -05:00
7 changed files with 437 additions and 271 deletions

View File

@@ -125,322 +125,321 @@ 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;
return true;
#else
return false;
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[3];
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
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 %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 error %3.3f %3.3f %3.3f", target[0], target[1], target[2]);
// 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];
}
position[X_AXIS] += gc_state.coord_offset[X_AXIS];
position[Y_AXIS] += gc_state.coord_offset[Y_AXIS];
position[Z_AXIS] += gc_state.coord_offset[Z_AXIS];
// 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];
// 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));
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
// 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 / KINEMATIC_SEGMENT_LENGTH);
KinematicError status;
float segment_dist = dist / ((float)segment_count); // distance of each segment...will be used for feedrate conversion
read_settings();
for (uint32_t segment = 1; segment <= segment_count; segment++) {
// determine this segment's target
seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment);
seg_target[Y_AXIS] = position[Y_AXIS] + (dy / float(segment_count) * segment);
seg_target[Z_AXIS] = position[Z_AXIS] + (dz / float(segment_count) * segment);
// 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]);
// calculate the delta motor angles
KinematicError status = delta_calcInverse(seg_target, motor_angles);
status = delta_calcInverse(position, motor_angles);
if (status == KinematicError::OUT_OF_RANGE) {
//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;
}
if (status == KinematicError ::NONE) {
float delta_distance = three_axis_dist(motor_angles, last_angle);
// 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 error %3.3f %3.3f %3.3f", target[0], target[1], target[2]);
}
// save angles for next distance calc
memcpy(last_angle, motor_angles, sizeof(motor_angles));
position[X_AXIS] += gc_state.coord_offset[X_AXIS];
position[Y_AXIS] += gc_state.coord_offset[Y_AXIS];
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 / KINEMATIC_SEGMENT_LENGTH);
float segment_dist = dist / ((float)segment_count); // distance of each segment...will be used for feedrate conversion
for (uint32_t segment = 1; segment <= segment_count; segment++) {
// determine this segment's target
seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment);
seg_target[Y_AXIS] = position[Y_AXIS] + (dy / float(segment_count) * segment);
seg_target[Z_AXIS] = position[Z_AXIS] + (dz / float(segment_count) * segment);
// calculate the delta motor angles
KinematicError status = delta_calcInverse(seg_target, motor_angles);
if (status == KinematicError ::NONE) {
float delta_distance = three_axis_dist(motor_angles, last_angle);
// save angles for next distance calc
memcpy(last_angle, motor_angles, sizeof(motor_angles));
if (pl_data->motion.rapidMotion) {
pl_data->feed_rate = feed_rate;
} else {
pl_data->feed_rate = (feed_rate * delta_distance / segment_dist);
}
mc_line(motor_angles, pl_data);
if (pl_data->motion.rapidMotion) {
pl_data->feed_rate = feed_rate;
} else {
pl_data->feed_rate = (feed_rate * delta_distance / segment_dist);
}
mc_line(motor_angles, pl_data);
} else {
if (show_error) {
// 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;
if (show_error) {
// 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];
// 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();
read_settings();
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin Soft Check %3.3f, %3.3f, %3.3f", target[0], target[1], target[2]);
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);
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;
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);
}
return (status == KinematicError::NONE);
}
// 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;
// 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;
status = delta_calcAngleYZ(cartesian[X_AXIS], cartesian[Y_AXIS], cartesian[Z_AXIS], angles[0]);
if (status != KinematicError ::NONE) {
return status;
}
status = delta_calcAngleYZ(cartesian[X_AXIS], cartesian[Y_AXIS], cartesian[Z_AXIS], angles[0]);
if (status != KinematicError ::NONE) {
status = delta_calcAngleYZ(cartesian[X_AXIS] * cos120 + cartesian[Y_AXIS] * sin120,
cartesian[Y_AXIS] * cos120 - cartesian[X_AXIS] * sin120,
cartesian[Z_AXIS],
angles[1]); // rotate coords to +120 deg
if (status != KinematicError ::NONE) {
return status;
}
status = delta_calcAngleYZ(cartesian[X_AXIS] * cos120 - cartesian[Y_AXIS] * sin120,
cartesian[Y_AXIS] * cos120 + cartesian[X_AXIS] * sin120,
cartesian[Z_AXIS],
angles[2]); // rotate coords to -120 deg
if (status != KinematicError ::NONE) {
return status;
}
//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;
}
status = delta_calcAngleYZ(cartesian[X_AXIS] * cos120 + cartesian[Y_AXIS] * sin120,
cartesian[Y_AXIS] * cos120 - cartesian[X_AXIS] * sin120,
cartesian[Z_AXIS],
angles[1]); // rotate coords to +120 deg
if (status != KinematicError ::NONE) {
return status;
// 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]));
float z1 = -rf * sin(angles[0]);
float y2 = (t + rf * cos(angles[1])) * sin30;
float x2 = y2 * tan60;
float z2 = -rf * sin(angles[1]);
float y3 = (t + rf * cos(angles[2])) * sin30;
float x3 = -y3 * tan60;
float z3 = -rf * sin(angles[2]);
float dnm = (y2 - y1) * x3 - (y3 - y1) * x2;
float w1 = y1 * y1 + z1 * z1;
float w2 = x2 * x2 + y2 * y2 + z2 * z2;
float w3 = x3 * x3 + y3 * y3 + z3 * z3;
// x = (a1*z + b1)/dnm
float a1 = (z2 - z1) * (y3 - y1) - (z3 - z1) * (y2 - y1);
float b1 = -((w2 - w1) * (y3 - y1) - (w3 - w1) * (y2 - y1)) / 2.0;
// y = (a2*z + b2)/dnm;
float a2 = -(z2 - z1) * x3 + (z3 - z1) * x2;
float b2 = ((w2 - w1) * x3 - (w3 - w1) * x2) / 2.0;
// a*z^2 + b*z + c = 0
float a = a1 * a1 + a2 * a2 + dnm * dnm;
float b = 2 * (a1 * b1 + a2 * (b2 - y1 * dnm) - z1 * dnm * dnm);
float c = (b2 - y1 * dnm) * (b2 - y1 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - re * re);
// discriminant
float d = b * b - (float)4.0 * a * c;
if (d < 0)
return -1; // non-existing point
catesian[Z_AXIS] = -(float)0.5 * (b + sqrt(d)) / a;
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) {
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
float a = (x0 * x0 + y0 * y0 + z0 * z0 + rf * rf - re * re - y1 * y1) / (2 * z0);
float b = (y1 - y0) / z0;
// discriminant
float d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf);
if (d < 0)
return KinematicError::OUT_OF_RANGE; // non-existing point
float yj = (y1 - a * b - sqrt(d)) / (b * b + 1); // choosing outer point
float zj = a + b * yj;
//theta = 180.0 * atan(-zj / (y1 - yj)) / M_PI + ((yj > y1) ? 180.0 : 0.0);
theta = atan(-zj / (y1 - yj)) + ((yj > y1) ? M_PI : 0.0);
if (theta < MAX_NEGATIVE_ANGLE) {
return KinematicError::ANGLE_TOO_NEGATIVE;
}
if (theta > MAX_POSITIVE_ANGLE) {
return KinematicError::ANGLE_TOO_POSITIVE;
}
return KinematicError::NONE;
}
status = delta_calcAngleYZ(cartesian[X_AXIS] * cos120 - cartesian[Y_AXIS] * sin120,
cartesian[Y_AXIS] * cos120 + cartesian[X_AXIS] * sin120,
cartesian[Z_AXIS],
angles[2]); // rotate coords to -120 deg
if (status != KinematicError ::NONE) {
return status;
// 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) {
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);
if (status == 0) {
// apply offsets and set the returned values
position[X_AXIS] = calc_fwd[X_AXIS] - gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS];
position[Y_AXIS] = calc_fwd[Y_AXIS] - gc_state.coord_system[Y_AXIS] + gc_state.coord_offset[Y_AXIS];
position[Z_AXIS] = calc_fwd[Z_AXIS] - gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS];
} else {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "MSG:Fwd Kin Error");
}
}
//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) {
float t = (f - e) * tan30 / 2;
float y1 = -(t + rf * cos(angles[0]));
float z1 = -rf * sin(angles[0]);
float y2 = (t + rf * cos(angles[1])) * sin30;
float x2 = y2 * tan60;
float z2 = -rf * sin(angles[1]);
float y3 = (t + rf * cos(angles[2])) * sin30;
float x3 = -y3 * tan60;
float z3 = -rf * sin(angles[2]);
float dnm = (y2 - y1) * x3 - (y3 - y1) * x2;
float w1 = y1 * y1 + z1 * z1;
float w2 = x2 * x2 + y2 * y2 + z2 * z2;
float w3 = x3 * x3 + y3 * y3 + z3 * z3;
// x = (a1*z + b1)/dnm
float a1 = (z2 - z1) * (y3 - y1) - (z3 - z1) * (y2 - y1);
float b1 = -((w2 - w1) * (y3 - y1) - (w3 - w1) * (y2 - y1)) / 2.0;
// y = (a2*z + b2)/dnm;
float a2 = -(z2 - z1) * x3 + (z3 - z1) * x2;
float b2 = ((w2 - w1) * x3 - (w3 - w1) * x2) / 2.0;
// a*z^2 + b*z + c = 0
float a = a1 * a1 + a2 * a2 + dnm * dnm;
float b = 2 * (a1 * b1 + a2 * (b2 - y1 * dnm) - z1 * dnm * dnm);
float c = (b2 - y1 * dnm) * (b2 - y1 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - re * re);
// discriminant
float d = b * b - (float)4.0 * a * c;
if (d < 0)
return -1; // non-existing point
catesian[Z_AXIS] = -(float)0.5 * (b + sqrt(d)) / a;
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) {
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
float a = (x0 * x0 + y0 * y0 + z0 * z0 + rf * rf - re * re - y1 * y1) / (2 * z0);
float b = (y1 - y0) / z0;
// discriminant
float d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf);
if (d < 0)
return KinematicError::OUT_OF_RANGE; // non-existing point
float yj = (y1 - a * b - sqrt(d)) / (b * b + 1); // choosing outer point
float zj = a + b * yj;
//theta = 180.0 * atan(-zj / (y1 - yj)) / M_PI + ((yj > y1) ? 180.0 : 0.0);
theta = atan(-zj / (y1 - yj)) + ((yj > y1) ? M_PI : 0.0);
if (theta < MAX_NEGATIVE_ANGLE) {
return KinematicError::ANGLE_TOO_NEGATIVE;
}
if (theta > MAX_POSITIVE_ANGLE) {
return KinematicError::ANGLE_TOO_POSITIVE;
}
return KinematicError::NONE;
}
// 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) {
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);
if (status == 0) {
// apply offsets and set the returned values
position[X_AXIS] = calc_fwd[X_AXIS] - gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS];
position[Y_AXIS] = calc_fwd[Y_AXIS] - gc_state.coord_system[Y_AXIS] + gc_state.coord_offset[Y_AXIS];
position[Z_AXIS] = calc_fwd[Z_AXIS] - gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS];
} 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;
return true;
#else
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "kinematics_pre_homing");
return false;
//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();
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();
read_settings();
calc_forward_kinematics(last_angle, last_cartesian);
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 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]);
// 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];
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
delay(1000); // give time for servo type homing
#endif
}
}
void user_m30() {}
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
}
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

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

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

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

@@ -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);
}

View File

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

View File

@@ -27,9 +27,10 @@ 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
;-DDEBUG_REPORT_HEAP_SIZE
;-DDEBUG_REPORT_STACK_FREE
-Wno-unused-
;-DDEBUG_REPORT_HEAP_SIZE
;-DDEBUG_REPORT_STACK_FREE
[env]
lib_deps =