From 4770843d3e73212bbde1039a5b3f7cb66361c4dd Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 15 Mar 2024 07:24:09 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../scripts/perception_replayer/perception_replayer.py | 7 +++++-- .../perception_replayer/perception_replayer_common.py | 3 ++- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py index 3977c2cd..5f9e9575 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py @@ -20,7 +20,8 @@ import sys from PyQt5.QtWidgets import QApplication -from geometry_msgs.msg import PoseWithCovarianceStamped, PoseStamped +from geometry_msgs.msg import PoseStamped +from geometry_msgs.msg import PoseWithCovarianceStamped from perception_replayer_common import PerceptionReplayerCommon import rclpy from time_manager_widget import TimeManagerWidget @@ -174,7 +175,8 @@ def publish_recorded_ego_pose(self): print("Published recorded ego pose as /initialpose") def publish_goal(self): - if (not self.rosbag_ego_odom_data): return + if not self.rosbag_ego_odom_data: + return goal_pose = PoseStamped() goal_pose.header.stamp = self.get_clock().now().to_msg() @@ -183,6 +185,7 @@ def publish_goal(self): self.goal_pose_publisher.publish(goal_pose) print("Published last recorded ego pose as /planning/mission_planning/goal") + if __name__ == "__main__": parser = argparse.ArgumentParser() parser.add_argument("-b", "--bag", help="rosbag", default=None) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py index 73bc3a4e..a30ac9b2 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py @@ -24,7 +24,8 @@ from autoware_auto_perception_msgs.msg import TrackedObjects from autoware_auto_perception_msgs.msg import TrafficSignalArray as AutoTrafficSignalArray from autoware_perception_msgs.msg import TrafficSignalArray -from geometry_msgs.msg import PoseWithCovarianceStamped, PoseStamped +from geometry_msgs.msg import PoseStamped +from geometry_msgs.msg import PoseWithCovarianceStamped from nav_msgs.msg import Odometry import psutil from rclpy.node import Node