Skip to content

Commit

Permalink
Fix circle arc condition (#20322)
Browse files Browse the repository at this point in the history
  • Loading branch information
yysh12 authored and thinkyhead committed Apr 29, 2021
1 parent 07954ed commit eba2937
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion Marlin/src/gcode/motion/G2_G3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ void plan_arc(
#endif

// Do a full circle if angular rotation is near 0 and the target is current position
if ((!angular_travel || NEAR_ZERO(angular_travel)) && NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) {
if (!angular_travel || (NEAR_ZERO(angular_travel) && NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis]))) {
// Preserve direction for circles
angular_travel = clockwise ? -RADIANS(360) : RADIANS(360);
}
Expand Down

0 comments on commit eba2937

Please sign in to comment.