From 56df6c40f60d33e8c6439b332c772d005d5f7e3f Mon Sep 17 00:00:00 2001 From: Marko Durkovic Date: Wed, 1 Mar 2023 20:18:38 +0100 Subject: [PATCH] Update code for current linter --- src/rosbags/rosbag1/reader.py | 2 +- src/rosbags/rosbag1/writer.py | 2 +- src/rosbags/rosbag2/reader.py | 2 +- src/rosbags/serde/cdr.py | 6 +++--- src/rosbags/serde/ros1.py | 4 ++-- src/rosbags/typesys/register.py | 3 +-- src/rosbags/typesys/types.py | 3 +-- tests/cdr.py | 4 ++-- tests/test_highlevel.py | 2 +- tests/test_reader1.py | 37 +++++++++++++++++---------------- tests/test_writer.py | 10 ++++----- 11 files changed, 37 insertions(+), 38 deletions(-) diff --git a/src/rosbags/rosbag1/reader.py b/src/rosbags/rosbag1/reader.py index 60569c91..5950b87f 100644 --- a/src/rosbags/rosbag1/reader.py +++ b/src/rosbags/rosbag1/reader.py @@ -366,7 +366,7 @@ class Reader: def open(self) -> None: """Open rosbag and read metadata.""" try: - self.bio = self.path.open('rb') + self.bio = self.path.open('rb') # pylint: disable=consider-using-with except OSError as err: raise ReaderError(f'Could not open file {str(self.path)!r}: {err.strerror}.') from err diff --git a/src/rosbags/rosbag1/writer.py b/src/rosbags/rosbag1/writer.py index ca480dcb..8b4f687b 100644 --- a/src/rosbags/rosbag1/writer.py +++ b/src/rosbags/rosbag1/writer.py @@ -192,7 +192,7 @@ class Writer: def open(self) -> None: """Open rosbag1 for writing.""" try: - self.bio = self.path.open('xb') + self.bio = self.path.open('xb') # pylint: disable=consider-using-with except FileExistsError: raise WriterError(f'{self.path} exists already, not overwriting.') from None diff --git a/src/rosbags/rosbag2/reader.py b/src/rosbags/rosbag2/reader.py index 27de18f8..02733a4e 100644 --- a/src/rosbags/rosbag2/reader.py +++ b/src/rosbags/rosbag2/reader.py @@ -138,7 +138,7 @@ class Reader: self.files: list[FileInformation] = self.metadata.get('files', [])[:] self.custom_data: dict[str, str] = self.metadata.get('custom_data', {}) - self.tmpdir: Optional[TemporaryDirectory] = None + self.tmpdir: Optional[TemporaryDirectory[str]] = None self.storage: Optional[StorageProtocol] = None except KeyError as exc: raise ReaderError(f'A metadata key is missing {exc!r}.') from None diff --git a/src/rosbags/serde/cdr.py b/src/rosbags/serde/cdr.py index 369b526e..2d3c983a 100644 --- a/src/rosbags/serde/cdr.py +++ b/src/rosbags/serde/cdr.py @@ -38,7 +38,7 @@ def generate_getsize_cdr(fields: list[Field]) -> tuple[CDRSerSize, int]: aligned = 8 iterators = tee([*fields, None]) - icurr = cast(Iterator[Field], iterators[0]) + icurr = cast('Iterator[Field]', iterators[0]) inext = iterators[1] next(inext) lines = [ @@ -178,7 +178,7 @@ def generate_serialize_cdr(fields: list[Field], endianess: str) -> CDRSer: # pylint: disable=too-many-branches,too-many-locals,too-many-statements aligned = 8 iterators = tee([*fields, None]) - icurr = cast(Iterator[Field], iterators[0]) + icurr = cast('Iterator[Field]', iterators[0]) inext = iterators[1] next(inext) lines = [ @@ -317,7 +317,7 @@ def generate_deserialize_cdr(fields: list[Field], endianess: str) -> CDRDeser: # pylint: disable=too-many-branches,too-many-locals,too-many-nested-blocks,too-many-statements aligned = 8 iterators = tee([*fields, None]) - icurr = cast(Iterator[Field], iterators[0]) + icurr = cast('Iterator[Field]', iterators[0]) inext = iterators[1] next(inext) lines = [ diff --git a/src/rosbags/serde/ros1.py b/src/rosbags/serde/ros1.py index 32a543db..f9cda30a 100644 --- a/src/rosbags/serde/ros1.py +++ b/src/rosbags/serde/ros1.py @@ -43,7 +43,7 @@ def generate_ros1_to_cdr( # pylint: disable=too-many-branches,too-many-locals,too-many-nested-blocks,too-many-statements aligned = 8 iterators = tee([*fields, None]) - icurr = cast(Iterator[Field], iterators[0]) + icurr = cast('Iterator[Field]', iterators[0]) inext = iterators[1] next(inext) funcname = 'ros1_to_cdr' if copy else 'getsize_ros1_to_cdr' @@ -199,7 +199,7 @@ def generate_cdr_to_ros1( # pylint: disable=too-many-branches,too-many-locals,too-many-nested-blocks,too-many-statements aligned = 8 iterators = tee([*fields, None]) - icurr = cast(Iterator[Field], iterators[0]) + icurr = cast('Iterator[Field]', iterators[0]) inext = iterators[1] next(inext) funcname = 'cdr_to_ros1' if copy else 'getsize_cdr_to_ros1' diff --git a/src/rosbags/typesys/register.py b/src/rosbags/typesys/register.py index 299c2bc6..3b562fba 100644 --- a/src/rosbags/typesys/register.py +++ b/src/rosbags/typesys/register.py @@ -46,7 +46,7 @@ def get_typehint(desc: tuple[int, Union[str, tuple[tuple[int, str], Optional[int sub = desc[1][0] if INTLIKE.match(sub[1]): - typ = 'bool8' if sub[1] == 'bool' else sub[1] + typ = 'bool_' if sub[1] == 'bool' else sub[1] return f'numpy.ndarray[Any, numpy.dtype[numpy.{typ}]]' assert isinstance(sub, tuple) return f'list[{get_typehint(sub)}]' @@ -71,7 +71,6 @@ def generate_python_code(typs: Typesdict) -> str: '', '# flake8: noqa N801', '# pylint: disable=invalid-name,too-many-instance-attributes,too-many-lines', - '# pylint: disable=unsubscriptable-object', '', 'from __future__ import annotations', '', diff --git a/src/rosbags/typesys/types.py b/src/rosbags/typesys/types.py index c4f7f175..f969a417 100644 --- a/src/rosbags/typesys/types.py +++ b/src/rosbags/typesys/types.py @@ -6,7 +6,6 @@ # flake8: noqa N801 # pylint: disable=invalid-name,too-many-instance-attributes,too-many-lines -# pylint: disable=unsubscriptable-object from __future__ import annotations @@ -608,7 +607,7 @@ class rcl_interfaces__msg__ParameterValue: double_value: float string_value: str byte_array_value: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] - bool_array_value: numpy.ndarray[Any, numpy.dtype[numpy.bool8]] + bool_array_value: numpy.ndarray[Any, numpy.dtype[numpy.bool_]] integer_array_value: numpy.ndarray[Any, numpy.dtype[numpy.int64]] double_array_value: numpy.ndarray[Any, numpy.dtype[numpy.float64]] string_array_value: list[str] diff --git a/tests/cdr.py b/tests/cdr.py index ee3d7f64..b28c5722 100644 --- a/tests/cdr.py +++ b/tests/cdr.py @@ -274,13 +274,13 @@ def serialize_array( if desc.valtype == Valtype.BASE: if desc.args == 'string': for item in val: - pos = serialize_string(rawdata, bmap, pos, cast(str, item)) + pos = serialize_string(rawdata, bmap, pos, cast('str', item)) return pos size = SIZEMAP[desc.args] pos = (pos + size - 1) & -size size *= len(val) - val = cast(NDArray[numpy.int_], val) + val = cast('NDArray[numpy.int_]', val) if (bmap is BASETYPEMAP_LE) != (sys.byteorder == 'little'): val = val.byteswap() # no inplace on readonly array rawdata[pos:pos + size] = memoryview(val.tobytes()) diff --git a/tests/test_highlevel.py b/tests/test_highlevel.py index 67189f42..defe1b1b 100644 --- a/tests/test_highlevel.py +++ b/tests/test_highlevel.py @@ -87,7 +87,7 @@ def test_anyreader1(bags1: Sequence[Path]) -> None: # pylint: disable=redefined reader = AnyReader(bags1) with pytest.raises(AnyReaderError, match='seems to be empty'): reader.open() - assert all(not x.bio for x in reader.readers) + assert all(not x.bio for x in reader.readers) # type: ignore[union-attr] with AnyReader(bags1[:3]) as reader: assert reader.duration == 15 diff --git a/tests/test_reader1.py b/tests/test_reader1.py index 20cb1e0f..f1d95228 100644 --- a/tests/test_reader1.py +++ b/tests/test_reader1.py @@ -69,8 +69,7 @@ def create_message( }, f'MSGCONTENT{msg}'.encode() -def write_bag( # pylint: disable=too-many-locals,too-many-statements - +def write_bag( # pylint: disable=too-many-locals bag: Path, header: dict[str, bytes], chunks: Sequence[Any] = (), @@ -129,8 +128,8 @@ def write_bag( # pylint: disable=too-many-locals,too-many-statements { 'op': b'\x05', 'compression': b'none', - 'size': pack(' None: x42_2_0 = IndexData(42, 2, 0) x43_3_0 = IndexData(43, 3, 0) - # flake8: noqa - # pylint: disable=unneeded-not assert not x42_1_0 < x42_2_0 assert x42_1_0 <= x42_2_0 assert x42_1_0 == x42_2_0 - assert not x42_1_0 != x42_2_0 + assert not x42_1_0 != x42_2_0 # noqa assert x42_1_0 >= x42_2_0 assert not x42_1_0 > x42_2_0 assert x42_1_0 < x43_3_0 assert x42_1_0 <= x43_3_0 - assert not x42_1_0 == x43_3_0 + assert not x42_1_0 == x43_3_0 # noqa assert x42_1_0 != x43_3_0 assert not x42_1_0 >= x43_3_0 assert not x42_1_0 > x43_3_0 @@ -215,10 +212,12 @@ def test_reader(tmp_path: Path) -> None: # pylint: disable=too-many-statements # single message write_bag( - bag, create_default_header(), chunks=[[ + bag, + create_default_header(), + chunks=[[ create_connection(), create_message(time=42), - ]] + ]], ) with Reader(bag) as reader: assert reader.message_count == 1 @@ -239,8 +238,8 @@ def test_reader(tmp_path: Path) -> None: # pylint: disable=too-many-statements create_connection(), create_message(time=10, msg=10), create_message(time=5, msg=5), - ] - ] + ], + ], ) with Reader(bag) as reader: assert reader.message_count == 2 @@ -266,8 +265,8 @@ def test_reader(tmp_path: Path) -> None: # pylint: disable=too-many-statements create_message(time=10, msg=10), create_connection(cid=2, topic=2), create_message(cid=2, time=5, msg=5), - ] - ] + ], + ], ) with Reader(bag) as reader: assert len(reader.topics.keys()) == 2 @@ -398,11 +397,13 @@ def test_failure_cases(tmp_path: Path) -> None: # pylint: disable=too-many-stat # bad uint8 field write_bag( - bag, create_default_header(), chunks=[[ + bag, + create_default_header(), + chunks=[[ ({}, {}), create_connection(), create_message(), - ]] + ]], ) with Reader(bag) as reader, \ pytest.raises(ReaderError, match='field \'op\''): diff --git a/tests/test_writer.py b/tests/test_writer.py index a39e3f50..551474ff 100644 --- a/tests/test_writer.py +++ b/tests/test_writer.py @@ -17,7 +17,7 @@ if TYPE_CHECKING: def test_writer(tmp_path: Path) -> None: """Test Writer.""" - path = (tmp_path / 'rosbag2') + path = tmp_path / 'rosbag2' with Writer(path) as bag: connection = bag.add_connection('/test', 'std_msgs/msg/Int8') bag.write(connection, 42, b'\x00') @@ -26,7 +26,7 @@ def test_writer(tmp_path: Path) -> None: assert (path / 'rosbag2.db3').exists() size = (path / 'rosbag2.db3').stat().st_size - path = (tmp_path / 'compress_none') + path = tmp_path / 'compress_none' bag = Writer(path) bag.set_compression(bag.CompressionMode.NONE, bag.CompressionFormat.ZSTD) with bag: @@ -37,7 +37,7 @@ def test_writer(tmp_path: Path) -> None: assert (path / 'compress_none.db3').exists() assert size == (path / 'compress_none.db3').stat().st_size - path = (tmp_path / 'compress_file') + path = tmp_path / 'compress_file' bag = Writer(path) bag.set_compression(bag.CompressionMode.FILE, bag.CompressionFormat.ZSTD) with bag: @@ -48,7 +48,7 @@ def test_writer(tmp_path: Path) -> None: assert not (path / 'compress_file.db3').exists() assert (path / 'compress_file.db3.zstd').exists() - path = (tmp_path / 'compress_message') + path = tmp_path / 'compress_message' bag = Writer(path) bag.set_compression(bag.CompressionMode.MESSAGE, bag.CompressionFormat.ZSTD) with bag: @@ -59,7 +59,7 @@ def test_writer(tmp_path: Path) -> None: assert (path / 'compress_message.db3').exists() assert size > (path / 'compress_message.db3').stat().st_size - path = (tmp_path / 'with_custom_data') + path = tmp_path / 'with_custom_data' bag = Writer(path) bag.open() bag.set_custom_data('key1', 'value1')