From 7804e2fd83a0280e39b14131385f4ad30b5df966 Mon Sep 17 00:00:00 2001 From: Matthijs van der Burgh Date: Mon, 18 Sep 2023 14:37:56 +0200 Subject: [PATCH] Fix mypy (#23) --- pykdl_ros/pykdl_ros/__init__.py | 52 ++++++++++--------- pykdl_ros/pyproject.toml | 1 + pykdl_ros/test/test_copyright.py | 2 +- pykdl_ros/test/test_flake8.py | 2 +- pykdl_ros/test/test_mypy.py | 4 +- pykdl_ros/test/test_pep257.py | 2 +- pykdl_ros/test/test_xmllint.py | 2 +- tf2_pykdl_ros/pyproject.toml | 1 + tf2_pykdl_ros/test/test_copyright.py | 2 +- tf2_pykdl_ros/test/test_flake8.py | 2 +- tf2_pykdl_ros/test/test_mypy.py | 4 +- tf2_pykdl_ros/test/test_pep257.py | 2 +- .../test/test_tf2_ros_integration.py | 52 +++++++++---------- .../test/test_tf2_ros_transform_node.py | 10 ++-- tf2_pykdl_ros/test/test_xmllint.py | 2 +- tf2_pykdl_ros/tf2_pykdl_ros/__init__.py | 2 +- 16 files changed, 73 insertions(+), 69 deletions(-) diff --git a/pykdl_ros/pykdl_ros/__init__.py b/pykdl_ros/pykdl_ros/__init__.py index 9a1f5b6..fedf3f8 100644 --- a/pykdl_ros/pykdl_ros/__init__.py +++ b/pykdl_ros/pykdl_ros/__init__.py @@ -24,22 +24,22 @@ def __init__(self, frame: kdl.Frame, stamp: Time, frame_id: str): self.frame = frame self.header = Header(frame_id=frame_id, stamp=stamp) - def __repr__(self): + def __repr__(self) -> str: pos = f"(x={self.frame.p.x()}, y={self.frame.p.y()}, z={self.frame.p.z()})" r, p, y = self.frame.M.GetRPY() rot = f"(r={r}, p={p}, y={y})" return f"FrameStamped({pos=}, {rot=} @ {self.header.frame_id})" - def __eq__(self, other): + def __eq__(self, other: object) -> bool: if isinstance(other, FrameStamped): - return self.frame == other.frame and self.header.frame_id == other.header.frame_id + return self.frame == other.frame and self.header.frame_id == other.header.frame_id # type: ignore else: return False - def __ne__(self, other): + def __ne__(self, other: object) -> bool: return not self.__eq__(other) - def __hash__(self): + def __hash__(self) -> int: return hash((self.frame, self.header.frame_id)) @classmethod @@ -82,7 +82,7 @@ class TwistStamped: __slots__ = "twist", "header" - def __init__(self, twist: kdl.Twist, stamp: Time, frame_id: str): + def __init__(self, twist: kdl.Twist, stamp: Time, frame_id: str) -> None: """ Construct a TwistStamped object. @@ -96,21 +96,21 @@ def __init__(self, twist: kdl.Twist, stamp: Time, frame_id: str): self.twist = twist self.header = Header(frame_id=frame_id, stamp=stamp) - def __repr__(self): + def __repr__(self) -> str: vel = f"(x={self.twist.vel.x()}, y={self.twist.vel.y()}, z={self.twist.vel.z()})" rot = f"(r={self.twist.rot.x()}, p={self.twist.rot.y()}, y={self.twist.rot.z()})" return f"TwistStamped({vel=}, {rot=} @ {self.header.frame_id})" - def __eq__(self, other): + def __eq__(self, other: object) -> bool: if isinstance(other, TwistStamped): - return self.twist == other.twist and self.header.frame_id == other.header.frame_id + return self.twist == other.twist and self.header.frame_id == other.header.frame_id # type: ignore else: return False - def __ne__(self, other): + def __ne__(self, other: object) -> bool: return not self.__eq__(other) - def __hash__(self): + def __hash__(self) -> int: return hash((self.twist, self.header.frame_id)) @classmethod @@ -126,7 +126,9 @@ def zero(cls, stamp: Time, frame_id: str) -> TwistStamped: return cls(twist, stamp, frame_id) @classmethod - def from_xyz_rpy(cls, vx: float, vy: float, vz: float, wx: float, wy: float, wz: float, stamp: Time, frame_id: str): + def from_xyz_rpy( + cls, vx: float, vy: float, vz: float, wx: float, wy: float, wz: float, stamp: Time, frame_id: str + ) -> TwistStamped: """ Construct a TwistStamped from velocity and XYZ and RPY. @@ -151,7 +153,7 @@ class VectorStamped: __slots__ = "vector", "header" - def __init__(self, vector: kdl.Vector, stamp: Time, frame_id: str): + def __init__(self, vector: kdl.Vector, stamp: Time, frame_id: str) -> None: """ Construct a VectorStamped object. @@ -165,20 +167,20 @@ def __init__(self, vector: kdl.Vector, stamp: Time, frame_id: str): self.vector = vector self.header = Header(frame_id=frame_id, stamp=stamp) - def __repr__(self): + def __repr__(self) -> str: xyz = f"(x={self.vector.x()}, y={self.vector.y()}, z={self.vector.z()})" return f"VectorStamped({xyz} @ {self.header.frame_id})" - def __eq__(self, other): + def __eq__(self, other: object) -> bool: if isinstance(other, VectorStamped): - return self.vector == other.vector and self.header.frame_id == other.header.frame_id + return self.vector == other.vector and self.header.frame_id == other.header.frame_id # type: ignore else: return False - def __ne__(self, other): + def __ne__(self, other: object) -> bool: return not self.__eq__(other) - def __hash__(self): + def __hash__(self) -> int: return hash((self.vector, self.header.frame_id)) @classmethod @@ -224,7 +226,7 @@ class WrenchStamped: __slots__ = "wrench", "header" - def __init__(self, wrench: kdl.Wrench, stamp: Time, frame_id: str): + def __init__(self, wrench: kdl.Wrench, stamp: Time, frame_id: str) -> None: """ Construct a WrenchStamped object. @@ -238,21 +240,21 @@ def __init__(self, wrench: kdl.Wrench, stamp: Time, frame_id: str): self.wrench = wrench self.header = Header(frame_id=frame_id, stamp=stamp) - def __repr__(self): + def __repr__(self) -> str: force = f"(x={self.wrench.force.x()}, y={self.wrench.force.y()}, z={self.wrench.force.z()})" torque = f"(x={self.wrench.torque.x()}, y={self.wrench.torque.y()}, z={self.wrench.torque.z()})" return f"WrenchStamped({force=}, {torque=} @ {self.header.frame_id})" - def __eq__(self, other): + def __eq__(self, other: object) -> bool: if isinstance(other, WrenchStamped): - return self.wrench == other.wrench and self.header.frame_id == other.header.frame_id + return self.wrench == other.wrench and self.header.frame_id == other.header.frame_id # type: ignore else: return False - def __ne__(self, other): + def __ne__(self, other: object) -> bool: return not self.__eq__(other) - def __hash__(self): + def __hash__(self) -> int: return hash((self.wrench, self.header.frame_id)) @classmethod @@ -270,7 +272,7 @@ def zero(cls, stamp: Time, frame_id: str) -> WrenchStamped: @classmethod def from_fxfyfz_txtytz( cls, fx: float, fy: float, fz: float, tx: float, ty: float, tz: float, stamp: Time, frame_id: str - ): + ) -> WrenchStamped: """ Construct a WrenchStamped from force and torque in XYZ. diff --git a/pykdl_ros/pyproject.toml b/pykdl_ros/pyproject.toml index 38819bc..f821013 100644 --- a/pykdl_ros/pyproject.toml +++ b/pykdl_ros/pyproject.toml @@ -12,6 +12,7 @@ skip_gitignore = true [tool.mypy] disallow_untyped_defs = true +ignore_missing_imports = true no_implicit_optional = true pretty = true show_error_codes = true diff --git a/pykdl_ros/test/test_copyright.py b/pykdl_ros/test/test_copyright.py index 60c2d1e..92fa7c8 100644 --- a/pykdl_ros/test/test_copyright.py +++ b/pykdl_ros/test/test_copyright.py @@ -20,6 +20,6 @@ @pytest.mark.skip(reason="No copyright header has been placed in the generated source file.") @pytest.mark.copyright @pytest.mark.linter -def test_copyright(): +def test_copyright() -> None: rc = main(argv=[".", "test"]) assert rc == 0, "Found errors" diff --git a/pykdl_ros/test/test_flake8.py b/pykdl_ros/test/test_flake8.py index a7e1231..39b6b72 100644 --- a/pykdl_ros/test/test_flake8.py +++ b/pykdl_ros/test/test_flake8.py @@ -18,6 +18,6 @@ @pytest.mark.flake8 @pytest.mark.linter -def test_flake8(): +def test_flake8() -> None: rc, errors = main_with_errors(argv=["--linelength", "120"]) assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors) diff --git a/pykdl_ros/test/test_mypy.py b/pykdl_ros/test/test_mypy.py index e09937c..fec3b18 100644 --- a/pykdl_ros/test/test_mypy.py +++ b/pykdl_ros/test/test_mypy.py @@ -18,7 +18,7 @@ @pytest.mark.mypy @pytest.mark.linter -def test_mypy(): +def test_mypy() -> None: try: import importlib.resources as _ # noqa: F401 except ModuleNotFoundError: @@ -28,4 +28,4 @@ def test_mypy(): # There is a bug in mypy that manifests when this try/except import pattern is # used: https://github.com/python/mypy/issues/1153 pytest.skip("This platform does not support mypy checking of importlib properly") - assert main(argv=[]) == 0, "Found errors" + assert main(argv=["--config", ""]) == 0, "Found errors" diff --git a/pykdl_ros/test/test_pep257.py b/pykdl_ros/test/test_pep257.py index 4eddb46..f4905db 100644 --- a/pykdl_ros/test/test_pep257.py +++ b/pykdl_ros/test/test_pep257.py @@ -18,6 +18,6 @@ @pytest.mark.linter @pytest.mark.pep257 -def test_pep257(): +def test_pep257() -> None: rc = main(argv=[".", "test"]) assert rc == 0, "Found code style errors / warnings" diff --git a/pykdl_ros/test/test_xmllint.py b/pykdl_ros/test/test_xmllint.py index bd9d09c..1f7e5c8 100644 --- a/pykdl_ros/test/test_xmllint.py +++ b/pykdl_ros/test/test_xmllint.py @@ -18,6 +18,6 @@ @pytest.mark.linter @pytest.mark.xmllint -def test_xmllint(): +def test_xmllint() -> None: rc = main(argv=[]) assert rc == 0, "Found errors" diff --git a/tf2_pykdl_ros/pyproject.toml b/tf2_pykdl_ros/pyproject.toml index 38819bc..f821013 100644 --- a/tf2_pykdl_ros/pyproject.toml +++ b/tf2_pykdl_ros/pyproject.toml @@ -12,6 +12,7 @@ skip_gitignore = true [tool.mypy] disallow_untyped_defs = true +ignore_missing_imports = true no_implicit_optional = true pretty = true show_error_codes = true diff --git a/tf2_pykdl_ros/test/test_copyright.py b/tf2_pykdl_ros/test/test_copyright.py index 60c2d1e..92fa7c8 100644 --- a/tf2_pykdl_ros/test/test_copyright.py +++ b/tf2_pykdl_ros/test/test_copyright.py @@ -20,6 +20,6 @@ @pytest.mark.skip(reason="No copyright header has been placed in the generated source file.") @pytest.mark.copyright @pytest.mark.linter -def test_copyright(): +def test_copyright() -> None: rc = main(argv=[".", "test"]) assert rc == 0, "Found errors" diff --git a/tf2_pykdl_ros/test/test_flake8.py b/tf2_pykdl_ros/test/test_flake8.py index a7e1231..39b6b72 100644 --- a/tf2_pykdl_ros/test/test_flake8.py +++ b/tf2_pykdl_ros/test/test_flake8.py @@ -18,6 +18,6 @@ @pytest.mark.flake8 @pytest.mark.linter -def test_flake8(): +def test_flake8() -> None: rc, errors = main_with_errors(argv=["--linelength", "120"]) assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors) diff --git a/tf2_pykdl_ros/test/test_mypy.py b/tf2_pykdl_ros/test/test_mypy.py index e09937c..fec3b18 100644 --- a/tf2_pykdl_ros/test/test_mypy.py +++ b/tf2_pykdl_ros/test/test_mypy.py @@ -18,7 +18,7 @@ @pytest.mark.mypy @pytest.mark.linter -def test_mypy(): +def test_mypy() -> None: try: import importlib.resources as _ # noqa: F401 except ModuleNotFoundError: @@ -28,4 +28,4 @@ def test_mypy(): # There is a bug in mypy that manifests when this try/except import pattern is # used: https://github.com/python/mypy/issues/1153 pytest.skip("This platform does not support mypy checking of importlib properly") - assert main(argv=[]) == 0, "Found errors" + assert main(argv=["--config", ""]) == 0, "Found errors" diff --git a/tf2_pykdl_ros/test/test_pep257.py b/tf2_pykdl_ros/test/test_pep257.py index 4eddb46..f4905db 100644 --- a/tf2_pykdl_ros/test/test_pep257.py +++ b/tf2_pykdl_ros/test/test_pep257.py @@ -18,6 +18,6 @@ @pytest.mark.linter @pytest.mark.pep257 -def test_pep257(): +def test_pep257() -> None: rc = main(argv=[".", "test"]) assert rc == 0, "Found code style errors / warnings" diff --git a/tf2_pykdl_ros/test/test_tf2_ros_integration.py b/tf2_pykdl_ros/test/test_tf2_ros_integration.py index c3aacfc..24934ee 100644 --- a/tf2_pykdl_ros/test/test_tf2_ros_integration.py +++ b/tf2_pykdl_ros/test/test_tf2_ros_integration.py @@ -26,66 +26,66 @@ def setUpClass(cls) -> None: cls.convert_reg = tf2_ros.ConvertRegistration() cls.transform_reg = tf2_ros.TransformRegistration() - def test_vector_stamped_from_msg(self): + def test_vector_stamped_from_msg(self) -> None: self.convert_reg.get_from_msg(VectorStamped) - def test_vector_stamped_to_msg(self): + def test_vector_stamped_to_msg(self) -> None: self.convert_reg.get_to_msg(VectorStamped) - def test_vector_stamped_convert(self): + def test_vector_stamped_convert(self) -> None: self.convert_reg.get_convert((PointStamped, VectorStamped)) self.convert_reg.get_convert((PoseStamped, VectorStamped)) self.convert_reg.get_convert((VectorStamped, PointStamped)) self.convert_reg.get_convert((VectorStamped, VectorStamped)) - def test_vector_stamped_transform(self): + def test_vector_stamped_transform(self) -> None: self.transform_reg.get(VectorStamped) - def test_frame_stamped_from_msg(self): + def test_frame_stamped_from_msg(self) -> None: self.convert_reg.get_from_msg(FrameStamped) - def test_frame_stamped_to_msg(self): + def test_frame_stamped_to_msg(self) -> None: self.convert_reg.get_to_msg(FrameStamped) - def test_frame_stamped_convert(self): + def test_frame_stamped_convert(self) -> None: self.convert_reg.get_convert((PoseStamped, FrameStamped)) self.convert_reg.get_convert((FrameStamped, PoseStamped)) self.convert_reg.get_convert((FrameStamped, FrameStamped)) - def test_frame_stamped_transform(self): + def test_frame_stamped_transform(self) -> None: self.transform_reg.get(FrameStamped) - def test_twist_stamped_from_msg(self): + def test_twist_stamped_from_msg(self) -> None: self.convert_reg.get_from_msg(TwistStamped) - def test_twist_stamp_to_msg(self): + def test_twist_stamp_to_msg(self) -> None: self.convert_reg.get_to_msg(TwistStamped) - def test_twist_stamp_convert(self): + def test_twist_stamp_convert(self) -> None: self.convert_reg.get_convert((TwistStampedMsg, TwistStamped)) self.convert_reg.get_convert((TwistStamped, TwistStampedMsg)) self.convert_reg.get_convert((TwistStamped, TwistStamped)) - def test_twist_stamped_transform(self): + def test_twist_stamped_transform(self) -> None: self.transform_reg.get(TwistStamped) - def test_wrench_stamped_from_msg(self): + def test_wrench_stamped_from_msg(self) -> None: self.convert_reg.get_from_msg(WrenchStamped) - def test_wrench_stamped_to_msg(self): + def test_wrench_stamped_to_msg(self) -> None: self.convert_reg.get_to_msg(WrenchStamped) - def test_wrench_stamped_convert(self): + def test_wrench_stamped_convert(self) -> None: self.convert_reg.get_convert((WrenchStampedMsg, WrenchStamped)) self.convert_reg.get_convert((WrenchStamped, WrenchStampedMsg)) self.convert_reg.get_convert((WrenchStamped, WrenchStamped)) - def test_wrench_stamped_transform(self): + def test_wrench_stamped_transform(self) -> None: self.transform_reg.get(WrenchStamped) class TestConvert(unittest.TestCase): - def test_point_stamped_vector_stamped(self): + def test_point_stamped_vector_stamped(self) -> None: p = PointStamped() p.header.frame_id = "map" p.header.stamp = Time(sec=4) @@ -100,7 +100,7 @@ def test_point_stamped_vector_stamped(self): self.assertEqual(v.header.stamp, p.header.stamp) self.assertEqual(v.header.frame_id, p.header.frame_id) - def test_vector_stamped_point_stamped(self): + def test_vector_stamped_point_stamped(self) -> None: v = VectorStamped.from_xyz(1, 2, 3, Time(sec=4), "map") p = tf2_ros.convert(v, PointStamped) self.assertIsInstance(p, PointStamped) @@ -110,7 +110,7 @@ def test_vector_stamped_point_stamped(self): self.assertEqual(p.header.stamp, v.header.stamp) self.assertEqual(p.header.frame_id, v.header.frame_id) - def test_pose_stamp_frame_stamped(self): + def test_pose_stamp_frame_stamped(self) -> None: p = PoseStamped() p.header.frame_id = "map" p.header.stamp = Time(sec=4) @@ -130,7 +130,7 @@ def test_pose_stamp_frame_stamped(self): self.assertEqual(f.header.stamp, p.header.stamp) self.assertEqual(f.header.frame_id, p.header.frame_id) - def test_frame_stamped_pose_stamped(self): + def test_frame_stamped_pose_stamped(self) -> None: f = FrameStamped.from_xyz_rpy(1, 2, 3, 4, 5, 6, Time(sec=4), "map") p = tf2_ros.convert(f, PoseStamped) self.assertIsInstance(p, PoseStamped) @@ -145,7 +145,7 @@ def test_frame_stamped_pose_stamped(self): self.assertEqual(p.header.stamp, f.header.stamp) self.assertEqual(p.header.frame_id, f.header.frame_id) - def test_twist_stamped_msg_twist_stamped(self): + def test_twist_stamped_msg_twist_stamped(self) -> None: msg = TwistStampedMsg() msg.header.frame_id = "map" msg.header.stamp = Time(sec=4) @@ -166,7 +166,7 @@ def test_twist_stamped_msg_twist_stamped(self): self.assertEqual(t.header.stamp, msg.header.stamp) self.assertEqual(t.header.frame_id, msg.header.frame_id) - def test_twist_stamped_twist_stamped_msg(self): + def test_twist_stamped_twist_stamped_msg(self) -> None: t = TwistStamped.from_xyz_rpy(1, 2, 3, 4, 5, 6, Time(sec=4), "map") msg = tf2_ros.convert(t, TwistStampedMsg) self.assertIsInstance(msg, TwistStampedMsg) @@ -179,7 +179,7 @@ def test_twist_stamped_twist_stamped_msg(self): self.assertEqual(msg.header.stamp, t.header.stamp) self.assertEqual(msg.header.frame_id, t.header.frame_id) - def test_wrench_stamped_msg_wrench_stamped(self): + def test_wrench_stamped_msg_wrench_stamped(self) -> None: msg = WrenchStampedMsg() msg.header.frame_id = "map" msg.header.stamp = Time(sec=4) @@ -200,7 +200,7 @@ def test_wrench_stamped_msg_wrench_stamped(self): self.assertEqual(w.header.stamp, msg.header.stamp) self.assertEqual(w.header.frame_id, msg.header.frame_id) - def test_wrench_stamped_wrench_stamped_msg(self): + def test_wrench_stamped_wrench_stamped_msg(self) -> None: w = WrenchStamped.from_fxfyfz_txtytz(1, 2, 3, 4, 5, 6, Time(sec=4), "map") msg = tf2_ros.convert(w, WrenchStampedMsg) self.assertIsInstance(msg, WrenchStampedMsg) @@ -229,7 +229,7 @@ def setUpClass(cls) -> None: cls.t.header.frame_id = "a" cls.t.child_frame_id = "b" - def test_transform(self): + def test_transform(self) -> None: f = FrameStamped(kdl.Frame(kdl.Rotation.RPY(1, 2, 3), kdl.Vector(1, 2, 3)), Time(sec=2), "b") transform_func = self.registration.get(type(f)) f_b = transform_func(f, self.t) @@ -241,7 +241,7 @@ def test_transform(self): (0.43595284407356577, -0.44443511344300074, 0.310622451065704, 0.7182870182434113), ) - def test_transform_incorrect_frame(self): + def test_transform_incorrect_frame(self) -> None: f2 = FrameStamped(kdl.Frame(kdl.Rotation.RPY(1, 2, 3), kdl.Vector(1, 2, 3)), Time(sec=2), "a") transform_func = self.registration.get(type(f2)) with self.assertRaises(AssertionError): diff --git a/tf2_pykdl_ros/test/test_tf2_ros_transform_node.py b/tf2_pykdl_ros/test/test_tf2_ros_transform_node.py index 387af3e..0be072f 100755 --- a/tf2_pykdl_ros/test/test_tf2_ros_transform_node.py +++ b/tf2_pykdl_ros/test/test_tf2_ros_transform_node.py @@ -43,21 +43,21 @@ def tearDownClass(cls) -> None: cls.node.destroy_node() rclpy.shutdown(context=cls.context) - def test_lookup_transform(self): + def test_lookup_transform(self) -> None: out = self.buffer.lookup_transform("a", "b", Time(sec=2), Duration(seconds=2)) self.assertEqual(out.transform.translation.x, 1) self.assertEqual(out.transform.rotation.x, 1) self.assertEqual(out.header.frame_id, "a") self.assertEqual(out.child_frame_id, "b") - def test_transform_vector(self): + def test_transform_vector(self) -> None: v = kdl.Vector(1, 2, 3) out: VectorStamped = self.buffer.transform(VectorStamped(v, Time(sec=2), "a"), "b") self.assertEqual(out.vector.x(), 0) self.assertEqual(out.vector.y(), -2) self.assertEqual(out.vector.z(), -3) - def test_transform_frame(self): + def test_transform_frame(self) -> None: f = kdl.Frame(kdl.Rotation.RPY(1, 2, 3), kdl.Vector(1, 2, 3)) out: FrameStamped = self.buffer.transform(FrameStamped(f, Time(sec=2), "a"), "b") self.assertEqual(out.frame.p.x(), 0) @@ -68,7 +68,7 @@ def test_transform_frame(self): (0.43595284407356577, -0.44443511344300074, 0.310622451065704, 0.7182870182434113), ) - def test_transform_twist(self): + def test_transform_twist(self) -> None: t = kdl.Twist(kdl.Vector(1, 2, 3), kdl.Vector(4, 5, 6)) out: TwistStamped = self.buffer.transform(TwistStamped(t, Time(sec=2), "a"), "b") self.assertEqual(out.twist.vel.x(), 1) @@ -78,7 +78,7 @@ def test_transform_twist(self): self.assertEqual(out.twist.rot.y(), -5) self.assertEqual(out.twist.rot.z(), -6) - def test_transform_wrench(self): + def test_transform_wrench(self) -> None: w = kdl.Wrench(kdl.Vector(1, 2, 3), kdl.Vector(4, 5, 6)) out: WrenchStamped = self.buffer.transform(WrenchStamped(w, Time(sec=2), "a"), "b") self.assertEqual(out.wrench.force.x(), 1) diff --git a/tf2_pykdl_ros/test/test_xmllint.py b/tf2_pykdl_ros/test/test_xmllint.py index bd9d09c..1f7e5c8 100644 --- a/tf2_pykdl_ros/test/test_xmllint.py +++ b/tf2_pykdl_ros/test/test_xmllint.py @@ -18,6 +18,6 @@ @pytest.mark.linter @pytest.mark.xmllint -def test_xmllint(): +def test_xmllint() -> None: rc = main(argv=[]) assert rc == 0, "Found errors" diff --git a/tf2_pykdl_ros/tf2_pykdl_ros/__init__.py b/tf2_pykdl_ros/tf2_pykdl_ros/__init__.py index fe3a0f7..86ce85a 100644 --- a/tf2_pykdl_ros/tf2_pykdl_ros/__init__.py +++ b/tf2_pykdl_ros/tf2_pykdl_ros/__init__.py @@ -67,7 +67,7 @@ def from_msg_vector(msg: Union[PointStamped, PoseStamped]) -> VectorStamped: tf2_ros.ConvertRegistration().add_from_msg(VectorStamped, from_msg_vector) -def convert_vector(vector: VectorStamped): +def convert_vector(vector: VectorStamped) -> VectorStamped: """ Convert a stamped PyKDL Vector to a stamped PyKDL Vector.