Skip to content

Commit

Permalink
py-mavros: fix flake8 errors
Browse files Browse the repository at this point in the history
Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>
  • Loading branch information
vooon committed Oct 10, 2024
1 parent 6959261 commit a386d80
Show file tree
Hide file tree
Showing 16 changed files with 20 additions and 33 deletions.
2 changes: 1 addition & 1 deletion mavros/mavros/base.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
from dataclasses import dataclass, field, fields
from functools import cached_property

import rclpy # noqa F401
import rclpy
import rclpy.node
import rclpy.qos

Expand Down
3 changes: 1 addition & 2 deletions mavros/mavros/cmd/checkid.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

import click
import rclpy.qos

from mavros_msgs.msg import Mavlink

from . import CliClient, cli, pass_client
Expand Down Expand Up @@ -66,7 +65,7 @@ def mavlink_source_cb(self, msg: Mavlink):
if ids in self.message_sources:
self.message_sources[ids].add(msg.msgid)
else:
self.message_sources[ids] = set((msg.msgid,))
self.message_sources[ids] = {msg.msgid}

self.messages_received += 1

Expand Down
7 changes: 3 additions & 4 deletions mavros/mavros/cmd/cmd.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@
import threading

import click
from sensor_msgs.msg import NavSatFix

from mavros_msgs.srv import (
CommandHome,
CommandInt,
Expand All @@ -25,6 +23,7 @@
CommandTriggerControl,
CommandTriggerInterval,
)
from sensor_msgs.msg import NavSatFix

from . import cli, pass_client
from .utils import bool2int, check_cmd_ret
Expand Down Expand Up @@ -86,7 +85,7 @@ def long(
check_cmd_ret(ctx, client, ret)


@cmd.command()
@cmd.command(name="int")
@click.option("-c", "--current", default=False, is_flag=True, help="Is current?")
@click.option(
"-a", "--autocontinue", default=False, is_flag=True, help="Is autocontinue?"
Expand All @@ -105,7 +104,7 @@ def long(
@click.argument("z", type=float)
@pass_client
@click.pass_context
def int(
def int_(
ctx,
client,
current,
Expand Down
5 changes: 2 additions & 3 deletions mavros/mavros/cmd/ftp.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
import typing

import click

from mavros_msgs.msg import FileEntry

from ..nuttx_crc32 import nuttx_crc32
Expand Down Expand Up @@ -54,7 +53,7 @@ def __enter__(self):

return self

def __exit__(self, type, value, traceback):
def __exit__(self, type, value, traceback): # noqa A002
if self.pbar:
self.pbar.__exit__(type, value, traceback)

Expand Down Expand Up @@ -107,7 +106,7 @@ def change_directory(ctx, client, path):
@click.argument("path", type=click.Path(exists=False), nargs=1, required=False)
@pass_client
@click.pass_context
def list(ctx, client, path):
def list(ctx, client, path): # noqa A002
"""List files and directories."""
path = resolve_path(path)
for ent in client.ftp.listdir(str(path)):
Expand Down
1 change: 0 additions & 1 deletion mavros/mavros/cmd/mission.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import typing

import click

from mavros_msgs.msg import Waypoint, WaypointList
from mavros_msgs.srv import (
WaypointClear,
Expand Down
2 changes: 1 addition & 1 deletion mavros/mavros/cmd/param.py
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ def get(client, param_id):
@click.argument("param_id", type=str)
@click.argument("value", type=str)
@pass_client
def set(client, param_id, value):
def set(client, param_id, value): # noqa A001
"""Set one parameter."""
if "." in value:
val = float(value)
Expand Down
1 change: 0 additions & 1 deletion mavros/mavros/cmd/safety.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
"""

import click

from mavros_msgs.srv import CommandBool, CommandLong

from . import cli, pass_client
Expand Down
5 changes: 2 additions & 3 deletions mavros/mavros/cmd/system.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import typing

import click

from mavros_msgs.msg import State
from mavros_msgs.srv import MessageInterval, SetMode, StreamRate

Expand Down Expand Up @@ -107,7 +106,7 @@ def wrap(f):
def rate(
ctx,
client,
all,
all, # noqa A002
raw_sensors,
ext_status,
rc_channels,
Expand Down Expand Up @@ -150,7 +149,7 @@ def set_rate(rate_arg: typing.Optional[int], id_: int):
@click.option("--id", type=int, metavar="MSGID", required=True, help="message id")
@click.option("--rate", type=float, metavar="RATE", required=True, help="message rate")
@pass_client
def message_interval(client, id, rate):
def message_interval(client, id, rate): # noqa A002
"""Set message interval."""
req = MessageInterval.Request(message_id=id, message_rate=rate)
client.system.cli_set_message_interval.call(req)
1 change: 0 additions & 1 deletion mavros/mavros/command.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
# https://github.com/mavlink/mavros/tree/master/LICENSE.md

import rclpy

from mavros_msgs.srv import (
CommandBool,
CommandHome,
Expand Down
7 changes: 3 additions & 4 deletions mavros/mavros/ftp.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,6 @@
import typing

import rclpy
from std_srvs.srv import Empty

from mavros_msgs.msg import FileEntry
from mavros_msgs.srv import (
FileChecksum,
Expand All @@ -27,6 +25,7 @@
FileTruncate,
FileWrite,
)
from std_srvs.srv import Empty

from .base import PluginModule, cached_property

Expand Down Expand Up @@ -54,7 +53,7 @@ def __init__(self, *, fm, name, mode):
def __del__(self):
self.close()

def open(self, path: str, mode: str):
def open(self, path: str, mode: str): # noqa A003
"""
Call open.
Expand Down Expand Up @@ -191,7 +190,7 @@ def cli_checksum(self) -> rclpy.node.Client:
def cli_reset(self) -> rclpy.node.Client:
return self.create_client(Empty, ("ftp", "reset"))

def open(self, path: str, mode: str = "r") -> FTPFile:
def open(self, path: str, mode: str = "r") -> FTPFile: # noqa A003
return FTPFile(fm=self, name=path, mode=mode)

def listdir(self, dir_path: str) -> typing.List[FileEntry]:
Expand Down
3 changes: 1 addition & 2 deletions mavros/mavros/mavlink.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,11 @@

import rclpy.time
from builtin_interfaces.msg import Time
from mavros_msgs.msg import Mavlink
from pymavlink import mavutil
from pymavlink.generator.mavcrc import x25crc # noqa F401
from std_msgs.msg import Header

from mavros_msgs.msg import Mavlink

from .utils import system_now

MAVLink_message = typing.TypeVar("MAVLink_message")
Expand Down
1 change: 0 additions & 1 deletion mavros/mavros/mission.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
from collections import OrderedDict

import rclpy

from mavros_msgs.msg import CommandCode, Waypoint, WaypointList
from mavros_msgs.srv import (
WaypointClear,
Expand Down
5 changes: 2 additions & 3 deletions mavros/mavros/param.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,13 @@
import typing

import rclpy
from mavros_msgs.msg import ParamEvent
from mavros_msgs.srv import ParamPull, ParamSetV2
from rcl_interfaces.msg import Parameter as ParameterMsg
from rcl_interfaces.msg import ParameterValue
from rcl_interfaces.srv import GetParameters, ListParameters, SetParameters
from rclpy.parameter import Parameter

from mavros_msgs.msg import ParamEvent
from mavros_msgs.srv import ParamPull, ParamSetV2

from .base import PARAMETERS_QOS, PluginModule, SubscriptionCallable, cached_property
from .utils import (
call_get_parameters,
Expand Down
3 changes: 1 addition & 2 deletions mavros/mavros/setpoint.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,11 @@
import rclpy
from geographic_msgs.msg import GeoPoseStamped
from geometry_msgs.msg import PoseStamped, Twist, TwistStamped, Vector3Stamped
from mavros_msgs.msg import AttitudeTarget, GlobalPositionTarget, PositionTarget, Thrust
from nav_msgs.msg import Path
from std_srvs.srv import Trigger
from trajectory_msgs.msg import MultiDOFJointTrajectory

from mavros_msgs.msg import AttitudeTarget, GlobalPositionTarget, PositionTarget, Thrust

from .base import SENSOR_QOS, PluginModule, SubscriptionCallable, cached_property

QOS = SENSOR_QOS
Expand Down
3 changes: 1 addition & 2 deletions mavros/mavros/system.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,9 @@
import typing

import rclpy
from sensor_msgs.msg import BatteryState

from mavros_msgs.msg import EstimatorStatus, ExtendedState, State, StatusText
from mavros_msgs.srv import MessageInterval, SetMode, StreamRate, VehicleInfoGet
from sensor_msgs.msg import BatteryState

from .base import (
SENSOR_QOS,
Expand Down
4 changes: 2 additions & 2 deletions mavros/setup.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ script_dir=$base/lib/mavros
install_scripts=$base/lib/mavros

[flake8]
# NOTE: based on ament_flake8.ini from Jazzy, but extended with Q000
extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,Q000
# NOTE: based on ament_flake8.ini from Jazzy, but extended with Q000,I100,I101
extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,Q000,I100,I101
import-order-style = google
max-line-length = 99
show-source = true
Expand Down

0 comments on commit a386d80

Please sign in to comment.