diff --git a/rb_ws/src/buggy/scripts/path_planner/path_planner.py b/rb_ws/src/buggy/scripts/path_planner/path_planner.py index 272f81d..2f91b1c 100755 --- a/rb_ws/src/buggy/scripts/path_planner/path_planner.py +++ b/rb_ws/src/buggy/scripts/path_planner/path_planner.py @@ -66,7 +66,7 @@ def __init__(self) -> None: #Publishers self.other_buggy_xtrack_publisher = self.create_publisher(Float64, "self/debug/other_buggy_xtrack", 10) self.traj_publisher = self.create_publisher(TrajectoryMsg, "self/cur_traj", 10) - + #Subscribers self.self_pose_subscriber = self.create_subscription(Odometry, 'self/state', self.self_pose_callback, 1) self.other_pose_subscriber = self.create_subscription(Odometry, 'other/state', self.other_pose_callback, 1) diff --git a/rb_ws/src/buggy/scripts/simulator/engine.py b/rb_ws/src/buggy/scripts/simulator/engine.py index f0fe89a..af2bdc5 100755 --- a/rb_ws/src/buggy/scripts/simulator/engine.py +++ b/rb_ws/src/buggy/scripts/simulator/engine.py @@ -1,6 +1,7 @@ #! /usr/bin/env python3 import threading import sys +import time import rclpy from rclpy.node import Node from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance @@ -9,7 +10,6 @@ from nav_msgs.msg import Odometry import numpy as np import utm -import time sys.path.append("/rb_ws/src/buggy/scripts") from util.constants import Constants @@ -184,12 +184,12 @@ def loop(self): def main(args=None): rclpy.init(args=args) sim = Simulator() - for i in range(500): + for _ in range(500): time.sleep(0.01) sim.publish() - - sim.get_logger().info("STARTED PUBLISHING") + + sim.get_logger().info("STARTED PUBLISHING") rclpy.spin(sim) sim.destroy_node()