Skip to content

Commit

Permalink
Fixing Bug: correct end of circular interpolation
Browse files Browse the repository at this point in the history
Fixed angle step calculation in circular path generation by dividing by step_num - 1 to ensure proper angular range coverage and avoid over/undersampling
  • Loading branch information
philipp1604 committed Oct 24, 2024
1 parent e427872 commit 7cd5888
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 4 deletions.
7 changes: 5 additions & 2 deletions src/pybullet_industrial/interpolation.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,12 @@ def build_circular_path(center: np.array, radius: float,
circular_path = np.zeros((2, step_num))
for j in range(step_num):
if clockwise:
path_angle = min_angle-j*(max_angle-min_angle)/step_num
path_angle = min_angle - j * \
(max_angle - min_angle) / (step_num - 1)
else:
path_angle = min_angle+j*(max_angle-min_angle)/step_num
path_angle = min_angle + j * \
(max_angle - min_angle) / (step_num - 1)

new_position = center + radius * \
np.array([np.cos(path_angle), np.sin(path_angle)])
circular_path[:, j] = new_position
Expand Down
8 changes: 6 additions & 2 deletions tests/test_interpolation.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,12 @@ def test_circular_interpolation(self):
start_point, end_point, radius, samples, axis, clockwise,
start_orientation, end_orientation)

# Expected positions for both orientations case (assuming planar interpolation is correct)
expected_positions = result_with_both_orientations.positions
# Expected positions for both orientations case (using the provided array)
expected_positions = np.array([
[1.0, 0.61731657, 0.29289322, 0.07612047, 0.0],
[0.0, 0.07612047, 0.29289322, 0.61731657, 1.0],
[0.0, 0.0, 0.0, 0.0, 0.0]
])

# Generate expected orientations using RotationSpline for SLERP
start_rot = R.from_quat(start_orientation)
Expand Down

0 comments on commit 7cd5888

Please sign in to comment.