diff --git a/pybotics/optimization.py b/pybotics/optimization.py index 396b19c1..840c0737 100644 --- a/pybotics/optimization.py +++ b/pybotics/optimization.py @@ -56,9 +56,9 @@ def apply_optimization_vector(self, vector: npt.NDArray[np.float64]) -> None: num_tool_parameters = np.sum(self.tool_mask) # extract vector segments - segments = np.split( + segments = np.split( # type: ignore vector, [num_kc_parameters, num_kc_parameters + num_tool_parameters] - ) # type: ignore + ) kc_segment = segments[0] tool_segment = segments[1] world_segment = segments[2] diff --git a/pybotics/robot.py b/pybotics/robot.py index 6fa75d0a..e9e2ea6b 100644 --- a/pybotics/robot.py +++ b/pybotics/robot.py @@ -192,9 +192,9 @@ def jacobian_flange( current_link = self.kinematic_chain.links[i] p = q[i] current_link_transform = current_link.transform(p) - current_transform = np.dot( + current_transform = np.dot( # type: ignore current_link_transform, current_transform - ) # type: ignore + ) return jacobian_flange diff --git a/tests/test_geometry.py b/tests/test_geometry.py index 2c1ecb79..d1f021dd 100644 --- a/tests/test_geometry.py +++ b/tests/test_geometry.py @@ -103,9 +103,9 @@ def test_rotation_matrix_x(angle: float) -> None: # check 3x3 rotation component actual_rotation = actual_matrix[:3, :3] expected_rotation = Rotation.from_rotvec(angle * axis_vector).as_matrix() - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual=actual_rotation, desired=expected_rotation, rtol=1e-05, atol=1e-08 - ) # type: ignore + ) @given( @@ -141,9 +141,9 @@ def test_rotation_matrix_y(angle: float) -> None: # check 3x3 rotation component actual_rotation = actual_matrix[:3, :3] expected_rotation = Rotation.from_rotvec(angle * axis_vector).as_matrix() - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual=actual_rotation, desired=expected_rotation, rtol=1e-05, atol=1e-08 - ) # type: ignore + ) @given( @@ -179,9 +179,9 @@ def test_rotation_matrix_z(angle: float) -> None: # check 3x3 rotation component actual_rotation = actual_matrix[:3, :3] expected_rotation = Rotation.from_rotvec(angle * axis_vector).as_matrix() - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual=actual_rotation, desired=expected_rotation, rtol=1e-05, atol=1e-08 - ) # type: ignore + ) @given( @@ -227,9 +227,9 @@ def test_vector_2_matrix( actual = pybotics.geometry.vector_2_matrix( d["vector"], convention=c # type: ignore ) - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual=actual, desired=d["transform"].reshape((4, 4)), atol=1e-6 - ) # type: ignore + ) # test exception with raises(PyboticsError): @@ -252,9 +252,9 @@ def test_matrix_2_vector( # TODO: implement other conversions # don't fail for NotImplementedError continue - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual=actual_vector, desired=d["vector"], atol=1e-6 - ) # type: ignore + ) def test_orientation() -> None: diff --git a/tests/test_optimization.py b/tests/test_optimization.py index 44014746..1550b9a6 100644 --- a/tests/test_optimization.py +++ b/tests/test_optimization.py @@ -42,7 +42,7 @@ def test_compute_absolute_errors(q: npt.NDArray[np.float64]) -> None: # test 2D input; i.e., many poses num_repeats = 10 - actual_error = compute_absolute_errors( + actual_error = compute_absolute_errors( # type: ignore qs=np.tile(q, (num_repeats, 1)), # type: ignore positions=np.tile(position_vector, (num_repeats, 1)), # type: ignore robot=robot, @@ -80,7 +80,7 @@ def test_compute_relative_errors( # test 2D input; i.e., many poses num_repeats = 10 - actual_error = compute_relative_errors( + actual_error = compute_relative_errors( # type: ignore qs_a=np.tile(q_a, (num_repeats, 1)), # type: ignore qs_b=np.tile(q_b, (num_repeats, 1)), # type: ignore distances=np.tile(distance, (num_repeats, 1)), # type: ignore @@ -99,9 +99,9 @@ def test_optimization() -> None: actual_robot.kinematic_chain.links[0].a += 0.1 # type: ignore # calculate fk - qs = np.tile( + qs = np.tile( # type: ignore np.linspace(start=-np.pi, stop=np.pi, num=100), (len(ur10()), 1) - ).transpose() # type: ignore + ).transpose() poses = np.array(list(map(actual_robot.fk, qs))) positions = poses[:, :-1, -1] @@ -121,20 +121,20 @@ def test_optimization() -> None: # validate atol = 1e-2 - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual=result.x, desired=handler.generate_optimization_vector(), atol=atol - ) # type: ignore - np.testing.assert_allclose( + ) + np.testing.assert_allclose( # type: ignore actual=handler.robot.kinematic_chain.vector, desired=actual_robot.kinematic_chain.vector, atol=atol, - ) # type: ignore - np.testing.assert_allclose( + ) + np.testing.assert_allclose( # type: ignore actual=handler.robot.tool.vector, desired=actual_robot.tool.vector, atol=atol - ) # type: ignore - np.testing.assert_allclose( + ) + np.testing.assert_allclose( # type: ignore actual=handler.robot.world_frame, desired=actual_robot.world_frame, atol=atol - ) # type: ignore + ) def test_handler_validate_transform_mask() -> None: diff --git a/tests/test_robot.py b/tests/test_robot.py index ec57f23e..1d693871 100644 --- a/tests/test_robot.py +++ b/tests/test_robot.py @@ -234,9 +234,9 @@ def test_ik(q: npt.NDArray[np.float64], q_offset: npt.NDArray[np.float64]) -> No # test the position with higher accuracy desired_position = pose[:-1, -1] actual_position = actual_pose[:-1, -1] - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore actual_position, desired_position, atol=1e-1 - ) # type: ignore + ) def test_random_joints() -> None: diff --git a/tests/test_tool.py b/tests/test_tool.py index 96459f07..95f4f4e6 100644 --- a/tests/test_tool.py +++ b/tests/test_tool.py @@ -16,6 +16,6 @@ def test_tool() -> None: p = np.array([1, 2, 3]) tool.position = p np.testing.assert_allclose(tool.position, p) # type: ignore - np.testing.assert_allclose( + np.testing.assert_allclose( # type: ignore tool.vector, matrix_2_vector(tool.matrix) - ) # type: ignore + )