Browse Source

Fix and combine JD condition

vanilla_fb_2.0.x
Scott Lahteine 4 years ago
parent
commit
c55475e8e7
  1. 18
      Marlin/src/module/planner.cpp

18
Marlin/src/module/planner.cpp

@ -2306,12 +2306,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
vmax_junction_sqr = junction_acceleration * junction_deviation_mm * sin_theta_d2 / (1.0f - sin_theta_d2);
if (block->millimeters < 1) {
const float neg = junction_cos_theta < 0 ? -1 : 1,
t = neg * junction_cos_theta;
// If angle is greater than 135 degrees (octagon), find speed for approximate arc
if (t > 0.7071067812f) {
// For small moves with >135° junction (octagon) find speed for approximate arc
if (block->millimeters < 1 && junction_cos_theta < -0.7071067812f) {
#if ENABLED(JD_USE_MATH_ACOS)
@ -2358,10 +2354,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
4.85301876f, 6.77019119f, 9.50873947f, 13.4009094f, 18.9188652f,
26.7320709f, 37.7884521f, 53.4292908f, 75.5522461f, 0.0f };
const float neg = junction_cos_theta < 0 ? -1 : 1,
t = neg * junction_cos_theta;
const int16_t idx = (t == 0.0f) ? 0 : __builtin_clz(uint16_t((1.0f - t) * jd_lut_tll)) - jd_lut_tll0;
float junction_theta = t * pgm_read_float(&jd_lut_k[idx]) + pgm_read_float(&jd_lut_b[idx]);
if (neg > 0) junction_theta = RADIANS(180) - junction_theta;
if (neg > 0) junction_theta = RADIANS(180) - junction_theta; // acos(-t)
#else
@ -2371,7 +2370,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// acos( t) = pi / 2 - asin(x)
// acos(-t) = pi - acos(t) ... pi / 2 + asin(x)
const float asinx = 0.032843707f
const float neg = junction_cos_theta < 0 ? -1 : 1,
t = neg * junction_cos_theta,
asinx = 0.032843707f
+ t * (-1.451838349f
+ t * ( 29.66153956f
+ t * (-131.1123477f
@ -2388,7 +2389,6 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
NOMORE(vmax_junction_sqr, limit_sqr);
}
}
}
// Get the lowest speed
vmax_junction_sqr = _MIN(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);

Loading…
Cancel
Save