Update code for current linters

This commit is contained in:
Marko Durkovic 2022-07-27 16:39:26 +02:00
parent 5257497a6a
commit 8333cfb971
6 changed files with 11 additions and 15 deletions

View File

@ -60,13 +60,13 @@ def main() -> None:
args = parser.parse_args()
if args.dst is not None and (args.src.suffix == '.bag') == (args.dst.suffix == '.bag'):
print('Source and destination rosbag versions must differ.') # noqa: T001
print('Source and destination rosbag versions must differ.') # noqa: T201
sys.exit(1)
try:
convert(**args.__dict__)
except ConverterError as err:
print(f'ERROR: {err}') # noqa: T001
print(f'ERROR: {err}') # noqa: T201
sys.exit(1)

View File

@ -254,8 +254,6 @@ string_literal
class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods
"""IDL file visitor."""
# pylint: disable=no-self-use
RULES = parse_grammar(GRAMMAR_IDL)
def __init__(self) -> None:

View File

@ -205,8 +205,6 @@ def denormalize_msgtype(typename: str) -> str:
class VisitorMSG(Visitor):
"""MSG file visitor."""
# pylint: disable=no-self-use
RULES = parse_grammar(GRAMMAR_MSG)
BASETYPES = {

View File

@ -254,7 +254,7 @@ def test_deserializer() -> None:
assert msg.header.frame_id == 'foo42'
field = msg.magnetic_field
assert (field.x, field.y, field.z) == (128., 128., 128.)
diag = numpy.diag(msg.magnetic_field_covariance.reshape(3, 3)) # type: ignore
diag = numpy.diag(msg.magnetic_field_covariance.reshape(3, 3))
assert (diag == [1., 1., 1.]).all()
msg_big = deserialize_cdr(*MSG_MAGN_BIG[:2])

View File

@ -133,16 +133,16 @@ def main() -> None:
"""Benchmark rosbag2 against rosbag2_py."""
path = Path(sys.argv[1])
try:
print('Comparing messages from rosbag2 and rosbag2_py.') # noqa: T001
print('Comparing messages from rosbag2 and rosbag2_py.') # noqa: T201
compare(path)
except AssertionError as err:
print(f'Comparison failed {err!r}') # noqa: T001
print(f'Comparison failed {err!r}') # noqa: T201
sys.exit(1)
print('Measuring execution times of rosbag2 and rosbag2_py.') # noqa: T001
print('Measuring execution times of rosbag2 and rosbag2_py.') # noqa: T201
time_py = timeit(lambda: read_deser_rosbag2_py(path), number=1)
time = timeit(lambda: read_deser_rosbag2(path), number=1)
print( # noqa: T001
print( # noqa: T201
f'Processing times:\n'
f'rosbag2_py {time_py:.3f}\n'
f'rosbag2 {time:.3f}\n'

View File

@ -67,7 +67,7 @@ def fixup_ros1(conns: List[rosbag.bag._Connection_Info]) -> None:
genpy.Duration.nanosec = property(lambda x: x.nsecs)
if conn := next((x for x in conns if x.datatype == 'sensor_msgs/CameraInfo'), None):
print('Patching CameraInfo') # noqa: T001
print('Patching CameraInfo') # noqa: T201
cls = rosbag.bag._get_message_type(conn) # pylint: disable=protected-access
cls.d = property(lambda x: x.D, lambda x, y: setattr(x, 'D', y)) # noqa: B010
cls.k = property(lambda x: x.K, lambda x, y: setattr(x, 'K', y)) # noqa: B010
@ -135,7 +135,7 @@ def main_bag1_bag1(path1: Path, path2: Path) -> None:
assert next(src1, None) is None
assert next(src2, None) is None
print('Bags are identical.') # noqa: T001
print('Bags are identical.') # noqa: T201
def main_bag1_bag2(path1: Path, path2: Path) -> None:
@ -160,12 +160,12 @@ def main_bag1_bag2(path1: Path, path2: Path) -> None:
assert next(src1, None) is None
assert next(src2, None) is None
print('Bags are identical.') # noqa: T001
print('Bags are identical.') # noqa: T201
if __name__ == '__main__':
if len(sys.argv) != 3:
print(f'Usage: {sys.argv} [rosbag1] [rosbag2]') # noqa: T001
print(f'Usage: {sys.argv} [rosbag1] [rosbag2]') # noqa: T201
sys.exit(1)
arg1 = Path(sys.argv[1])
arg2 = Path(sys.argv[2])