Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jun 13, 2024
1 parent 59c34bd commit bcfaad5
Show file tree
Hide file tree
Showing 57 changed files with 127 additions and 209 deletions.
5 changes: 1 addition & 4 deletions autoware_msg_bag_converter/autoware_msg_bag_converter/bag.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from rosbag2_py import ConverterOptions
from rosbag2_py import SequentialReader
from rosbag2_py import SequentialWriter
from rosbag2_py import StorageOptions
from rosbag2_py import ConverterOptions, SequentialReader, SequentialWriter, StorageOptions


def get_default_converter_options() -> ConverterOptions:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,9 @@
# https://github.com/ros2/rosbag2/blob/rolling/rosbag2_py/test/test_sequential_writer.py
# https://github.com/ros2/rosbag2/blob/rolling/rosbag2_py/test/test_reindexer.py

from rosbag2_py import Reindexer
from rosbag2_py import TopicMetadata
from rosbag2_py import Reindexer, TopicMetadata

from autoware_msg_bag_converter.bag import create_reader
from autoware_msg_bag_converter.bag import create_writer
from autoware_msg_bag_converter.bag import get_default_storage_options
from autoware_msg_bag_converter.bag import create_reader, create_writer, get_default_storage_options


def change_topic_type(old_type: TopicMetadata) -> TopicMetadata:
Expand Down
5 changes: 2 additions & 3 deletions bag2lanelet/scripts/bag2lanelet.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,10 @@
#!/bin/env python3
import argparse
from datetime import datetime
import os
import pathlib
from datetime import datetime

from bag2way import bag2pose
from bag2way import pose2line
from bag2way import bag2pose, pose2line
from lanelet_xml import LaneletMap


Expand Down
4 changes: 2 additions & 2 deletions bag2lanelet/scripts/bag2map.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
#!/bin/env python3
import argparse
from datetime import datetime
import os
import pathlib
from datetime import datetime

from bag2way import bag2point_stamped
import folium
from bag2way import bag2point_stamped
from tools.bag2lanelet.scripts.lanelet_xml import LaneletMap


Expand Down
2 changes: 1 addition & 1 deletion bag2lanelet/scripts/bag2trajectory.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@
import argparse
import pathlib

from bag2way import bag2pose
import numpy as np
import tf_transformations
from bag2way import bag2pose


def generate(input_path, output_path):
Expand Down
6 changes: 2 additions & 4 deletions bag2lanelet/scripts/bag2way.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,10 @@
from datetime import datetime

import numpy as np
import tf_transformations
from rclpy.serialization import deserialize_message
from rosbag2_py import ConverterOptions
from rosbag2_py import SequentialReader
from rosbag2_py import StorageOptions
from rosbag2_py import ConverterOptions, SequentialReader, StorageOptions
from rosidl_runtime_py.utilities import get_message
import tf_transformations


def create_reader(bag_dir: str) -> SequentialReader:
Expand Down
2 changes: 1 addition & 1 deletion bag2lanelet/scripts/lanelet_xml.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from xml.dom.minidom import parseString
import xml.etree.ElementTree as ET
from xml.dom.minidom import parseString

from mgrspy import mgrs

Expand Down
5 changes: 2 additions & 3 deletions common/tier4_debug_tools/scripts/pose2tf.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,10 @@
import argparse
import sys

from geometry_msgs.msg import PoseStamped
from geometry_msgs.msg import TransformStamped
import rclpy
from rclpy.node import Node
import tf2_ros
from geometry_msgs.msg import PoseStamped, TransformStamped
from rclpy.node import Node


class Pose2TfNode(Node):
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/scripts/self_pose_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from geometry_msgs.msg import PoseStamped
import rclpy
from geometry_msgs.msg import PoseStamped
from rclpy.node import Node
from tf2_ros import LookupException
from tf2_ros.buffer import Buffer
Expand Down
4 changes: 2 additions & 2 deletions common/tier4_debug_tools/scripts/stop_reason2pose.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,10 @@
import math
import sys

from case_converter import pascal2snake
from geometry_msgs.msg import PoseStamped
import numpy as np
import rclpy
from case_converter import pascal2snake
from geometry_msgs.msg import PoseStamped
from rclpy.node import Node
from rtree import index
from self_pose_listener import SelfPoseListener
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/scripts/tf2pose.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
import argparse
import sys

from geometry_msgs.msg import PoseStamped
import rclpy
from geometry_msgs.msg import PoseStamped
from rclpy.node import Node
from tf2_ros import LookupException
from tf2_ros.buffer import Buffer
Expand Down
2 changes: 1 addition & 1 deletion control/control_debug_tools/scripts/consistency_checker.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
import argparse
import math

from ament_index_python.packages import get_package_share_directory
import yaml
from ament_index_python.packages import get_package_share_directory


def read_yaml(file_path):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,10 @@
import dataclasses
import sqlite3

import numpy as np
from constants import THRESHOLD_FOR_INITIALIZED_ERROR
from geometry_msgs.msg import PoseWithCovarianceStamped
from geometry_msgs.msg import TwistWithCovarianceStamped
from geometry_msgs.msg import PoseWithCovarianceStamped, TwistWithCovarianceStamped
from nav_msgs.msg import Odometry
import numpy as np
from rclpy.serialization import deserialize_message
from rosidl_runtime_py.utilities import get_message
from scipy.spatial.transform import Rotation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,10 @@
from pathlib import Path
from threading import Thread

from bag_load_utils import BagFileEvaluator
import numpy as np
from plot_utils import plot_bag_compare
import rclpy
from bag_load_utils import BagFileEvaluator
from plot_utils import plot_bag_compare
from rclpy.node import Node

PARAMS = {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from constants import THRESHOLD_FOR_INITIALIZED_ERROR
import matplotlib.pyplot as plt
import numpy as np
from constants import THRESHOLD_FOR_INITIALIZED_ERROR


def plot_thresholds(recall_list, lower_bound, threshold, scale, save_path=None):
Expand Down
16 changes: 6 additions & 10 deletions planning/planning_debug_tools/scripts/closest_velocity_checker.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,23 +16,19 @@

import time

import numpy as np
import rclpy
from autoware_control_msgs.msg import Control as AckermannControlCommand
from autoware_planning_msgs.msg import Path
from autoware_planning_msgs.msg import Trajectory
from autoware_vehicle_msgs.msg import Engage
from autoware_vehicle_msgs.msg import VelocityReport
from autoware_planning_msgs.msg import Path, Trajectory
from autoware_vehicle_msgs.msg import Engage, VelocityReport
from geometry_msgs.msg import Pose
from nav_msgs.msg import Odometry
import numpy as np
import rclpy
from rclpy.node import Node
from tf2_ros import LookupException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener
from tier4_debug_msgs.msg import Float32MultiArrayStamped
from tier4_debug_msgs.msg import Float32Stamped
from tier4_planning_msgs.msg import PathWithLaneId
from tier4_planning_msgs.msg import VelocityLimit
from tier4_debug_msgs.msg import Float32MultiArrayStamped, Float32Stamped
from tier4_planning_msgs.msg import PathWithLaneId, VelocityLimit

REF_LINK = "map"
SELF_LINK = "base_link"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,12 @@
import functools
import sys

from PyQt5.QtWidgets import QApplication
from geometry_msgs.msg import PoseStamped
from geometry_msgs.msg import PoseWithCovarianceStamped
from perception_replayer_common import PerceptionReplayerCommon
import rclpy
from geometry_msgs.msg import PoseStamped, PoseWithCovarianceStamped
from perception_replayer_common import PerceptionReplayerCommon
from PyQt5.QtWidgets import QApplication
from time_manager_widget import TimeManagerWidget
from utils import create_empty_pointcloud
from utils import translate_objects_coordinate
from utils import create_empty_pointcloud, translate_objects_coordinate


class PerceptionReplayer(PerceptionReplayerCommon):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,27 +15,26 @@
# limitations under the License.

import os
from subprocess import CalledProcessError
from subprocess import check_output
import time
from subprocess import CalledProcessError, check_output

from autoware_perception_msgs.msg import DetectedObjects
from autoware_perception_msgs.msg import PredictedObjects
from autoware_perception_msgs.msg import TrackedObjects
from autoware_perception_msgs.msg import TrafficLightElement
from autoware_perception_msgs.msg import TrafficLightGroup
from autoware_perception_msgs.msg import TrafficLightGroupArray
from geometry_msgs.msg import PoseStamped
from geometry_msgs.msg import PoseWithCovarianceStamped
from nav_msgs.msg import Odometry
import psutil
from autoware_perception_msgs.msg import (
DetectedObjects,
PredictedObjects,
TrackedObjects,
TrafficLightElement,
TrafficLightGroup,
TrafficLightGroupArray,
)
from geometry_msgs.msg import PoseStamped, PoseWithCovarianceStamped
from nav_msgs.msg import Odometry
from rclpy.node import Node
from rclpy.serialization import deserialize_message
from rosbag2_py import StorageFilter
from rosidl_runtime_py.utilities import get_message
from sensor_msgs.msg import PointCloud2
from utils import get_starting_time
from utils import open_reader
from utils import get_starting_time, open_reader


class PerceptionReplayerCommon(Node):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,13 @@
# limitations under the License.

import argparse
from collections import deque
import pickle
from collections import deque

import numpy as np
from perception_replayer_common import PerceptionReplayerCommon
import rclpy
from utils import StopWatch
from utils import create_empty_pointcloud
from utils import translate_objects_coordinate
from perception_replayer_common import PerceptionReplayerCommon
from utils import StopWatch, create_empty_pointcloud, translate_objects_coordinate

dist_eps = 1e-2 # (meters)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,7 @@
# limitations under the License.

from PyQt5 import QtCore
from PyQt5.QtWidgets import QGridLayout
from PyQt5.QtWidgets import QMainWindow
from PyQt5.QtWidgets import QPushButton
from PyQt5.QtWidgets import QSizePolicy
from PyQt5.QtWidgets import QSlider
from PyQt5.QtWidgets import QWidget
from PyQt5.QtWidgets import QGridLayout, QMainWindow, QPushButton, QSizePolicy, QSlider, QWidget


# With QSlider, the slider's handle cannot be captured if the mouse cursor is not the handle position when pressing the mouse.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,11 @@
import math
import time

from geometry_msgs.msg import Quaternion
import numpy as np
import rosbag2_py
from sensor_msgs.msg import PointCloud2
from sensor_msgs.msg import PointField
from tf_transformations import euler_from_quaternion
from tf_transformations import quaternion_from_euler
from geometry_msgs.msg import Quaternion
from sensor_msgs.msg import PointCloud2, PointField
from tf_transformations import euler_from_quaternion, quaternion_from_euler


def get_starting_time(uri: str):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,9 @@


import argparse
from collections import deque
import os
import sys
from collections import deque

import rclpy
from rclpy.node import Node
Expand Down
17 changes: 6 additions & 11 deletions planning/planning_debug_tools/scripts/trajectory_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,24 +16,19 @@

import argparse

from autoware_planning_msgs.msg import Path
from autoware_planning_msgs.msg import PathPoint
from autoware_planning_msgs.msg import Trajectory
from autoware_planning_msgs.msg import TrajectoryPoint
from autoware_vehicle_msgs.msg import VelocityReport
from geometry_msgs.msg import Pose
from matplotlib import animation
import matplotlib.pyplot as plt
import message_filters
from nav_msgs.msg import Odometry
import numpy as np
import rclpy
from autoware_planning_msgs.msg import Path, PathPoint, Trajectory, TrajectoryPoint
from autoware_vehicle_msgs.msg import VelocityReport
from geometry_msgs.msg import Pose
from matplotlib import animation
from nav_msgs.msg import Odometry
from rclpy.node import Node
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener
from tier4_planning_msgs.msg import PathPointWithLaneId
from tier4_planning_msgs.msg import PathWithLaneId
from tier4_planning_msgs.msg import VelocityLimit
from tier4_planning_msgs.msg import PathPointWithLaneId, PathWithLaneId, VelocityLimit

parser = argparse.ArgumentParser()
parser.add_argument("-l", "--length", help="max arclength in plot")
Expand Down
3 changes: 1 addition & 2 deletions simulator/simulator_compatibility_test/setup.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
from warnings import simplefilter

from pkg_resources import PkgResourcesDeprecationWarning
from setuptools import SetuptoolsDeprecationWarning
from setuptools import setup
from setuptools import SetuptoolsDeprecationWarning, setup

# cspell: ignore moraisim

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from morai_msgs.srv import MoraiEventCmdSrv
import rclpy
from morai_msgs.srv import MoraiEventCmdSrv
from rclpy.node import Node


Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,9 @@
import rclpy
from autoware_control_msgs.msg import Control as AckermannControlCommand
from autoware_control_msgs.msg import Lateral as LateralCommand
from autoware_control_msgs.msg import Longitudinal as LongitudinalCommand
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy


class ControlCommand(Node):
Expand Down
Loading

0 comments on commit bcfaad5

Please sign in to comment.