Update code for current linters
This commit is contained in:
parent
5257497a6a
commit
8333cfb971
@ -60,13 +60,13 @@ def main() -> None:
|
|||||||
|
|
||||||
args = parser.parse_args()
|
args = parser.parse_args()
|
||||||
if args.dst is not None and (args.src.suffix == '.bag') == (args.dst.suffix == '.bag'):
|
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)
|
sys.exit(1)
|
||||||
|
|
||||||
try:
|
try:
|
||||||
convert(**args.__dict__)
|
convert(**args.__dict__)
|
||||||
except ConverterError as err:
|
except ConverterError as err:
|
||||||
print(f'ERROR: {err}') # noqa: T001
|
print(f'ERROR: {err}') # noqa: T201
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@ -254,8 +254,6 @@ string_literal
|
|||||||
class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods
|
class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods
|
||||||
"""IDL file visitor."""
|
"""IDL file visitor."""
|
||||||
|
|
||||||
# pylint: disable=no-self-use
|
|
||||||
|
|
||||||
RULES = parse_grammar(GRAMMAR_IDL)
|
RULES = parse_grammar(GRAMMAR_IDL)
|
||||||
|
|
||||||
def __init__(self) -> None:
|
def __init__(self) -> None:
|
||||||
|
|||||||
@ -205,8 +205,6 @@ def denormalize_msgtype(typename: str) -> str:
|
|||||||
class VisitorMSG(Visitor):
|
class VisitorMSG(Visitor):
|
||||||
"""MSG file visitor."""
|
"""MSG file visitor."""
|
||||||
|
|
||||||
# pylint: disable=no-self-use
|
|
||||||
|
|
||||||
RULES = parse_grammar(GRAMMAR_MSG)
|
RULES = parse_grammar(GRAMMAR_MSG)
|
||||||
|
|
||||||
BASETYPES = {
|
BASETYPES = {
|
||||||
|
|||||||
@ -254,7 +254,7 @@ def test_deserializer() -> None:
|
|||||||
assert msg.header.frame_id == 'foo42'
|
assert msg.header.frame_id == 'foo42'
|
||||||
field = msg.magnetic_field
|
field = msg.magnetic_field
|
||||||
assert (field.x, field.y, field.z) == (128., 128., 128.)
|
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()
|
assert (diag == [1., 1., 1.]).all()
|
||||||
|
|
||||||
msg_big = deserialize_cdr(*MSG_MAGN_BIG[:2])
|
msg_big = deserialize_cdr(*MSG_MAGN_BIG[:2])
|
||||||
|
|||||||
@ -133,16 +133,16 @@ def main() -> None:
|
|||||||
"""Benchmark rosbag2 against rosbag2_py."""
|
"""Benchmark rosbag2 against rosbag2_py."""
|
||||||
path = Path(sys.argv[1])
|
path = Path(sys.argv[1])
|
||||||
try:
|
try:
|
||||||
print('Comparing messages from rosbag2 and rosbag2_py.') # noqa: T001
|
print('Comparing messages from rosbag2 and rosbag2_py.') # noqa: T201
|
||||||
compare(path)
|
compare(path)
|
||||||
except AssertionError as err:
|
except AssertionError as err:
|
||||||
print(f'Comparison failed {err!r}') # noqa: T001
|
print(f'Comparison failed {err!r}') # noqa: T201
|
||||||
sys.exit(1)
|
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_py = timeit(lambda: read_deser_rosbag2_py(path), number=1)
|
||||||
time = timeit(lambda: read_deser_rosbag2(path), number=1)
|
time = timeit(lambda: read_deser_rosbag2(path), number=1)
|
||||||
print( # noqa: T001
|
print( # noqa: T201
|
||||||
f'Processing times:\n'
|
f'Processing times:\n'
|
||||||
f'rosbag2_py {time_py:.3f}\n'
|
f'rosbag2_py {time_py:.3f}\n'
|
||||||
f'rosbag2 {time:.3f}\n'
|
f'rosbag2 {time:.3f}\n'
|
||||||
|
|||||||
@ -67,7 +67,7 @@ def fixup_ros1(conns: List[rosbag.bag._Connection_Info]) -> None:
|
|||||||
genpy.Duration.nanosec = property(lambda x: x.nsecs)
|
genpy.Duration.nanosec = property(lambda x: x.nsecs)
|
||||||
|
|
||||||
if conn := next((x for x in conns if x.datatype == 'sensor_msgs/CameraInfo'), None):
|
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 = 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.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
|
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(src1, None) is None
|
||||||
assert next(src2, 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:
|
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(src1, None) is None
|
||||||
assert next(src2, 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 __name__ == '__main__':
|
||||||
if len(sys.argv) != 3:
|
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)
|
sys.exit(1)
|
||||||
arg1 = Path(sys.argv[1])
|
arg1 = Path(sys.argv[1])
|
||||||
arg2 = Path(sys.argv[2])
|
arg2 = Path(sys.argv[2])
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user