Skip to content

Commit

Permalink
more cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
TiaSinghania committed Feb 5, 2024
1 parent f79d1e9 commit 507462b
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 20 deletions.
14 changes: 7 additions & 7 deletions rb_ws/src/buggy/scripts/2d_sim/engine.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
#! /usr/bin/env python3
import sys
import threading
from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance
from std_msgs.msg import Float64
from sensor_msgs.msg import NavSatFix
from nav_msgs.msg import Odometry
import threading
import numpy as np
import utm
import sys
import rospy


Expand Down Expand Up @@ -35,10 +35,10 @@ def __init__(self, starting_pose, velocity, buggy_name):
self.steering_subscriber = rospy.Subscriber(
buggy_name + "/input/steering", Float64, self.update_steering_angle
)
# To read from velocity
# To read from velocity
self.velocity_subscriber = rospy.Subscriber(
buggy_name + "/velocity", Float64, self.update_velocity
)
)
# to plot on Foxglove (no noise)
self.navsatfix_publisher = rospy.Publisher(
buggy_name + "/state/pose_navsat", NavSatFix, queue_size=1
Expand Down Expand Up @@ -66,7 +66,7 @@ def __init__(self, starting_pose, velocity, buggy_name):
# utm_coords = utm.from_latlon(Simulator.START_LAT, Simulator.START_LONG)
# self.e_utm = utm_coords[0]
# self.n_utm = utm_coords[1]
self.e_utm, self.n_utm, self.heading = self.starting_poses[starting_pose]
self.e_utm, self.n_utm, self.heading = self.starting_poses[starting_pose]
self.velocity = velocity # m/s

self.steering_angle = 0 # degrees
Expand All @@ -92,7 +92,7 @@ def update_velocity(self, data: Float64):
source (string): whether incoming data is manual or simulated
"""
with self.lock:
self.velocity = data.data
self.velocity = data.data
def get_steering_arc(self):
# Adapted from simulator.py (Joseph Li)
# calculate the radius of the steering arc
Expand Down Expand Up @@ -126,7 +126,7 @@ def dynamics(self, state, v):

def step(self):
"""Complete the step at a certain Hz here. Do physics"""
with self.lock:
with self.lock:
heading = self.heading
e_utm = self.e_utm
n_utm = self.n_utm
Expand Down
10 changes: 4 additions & 6 deletions rb_ws/src/buggy/scripts/2d_sim/velocity_ui.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
#! /usr/bin/env python3
import rospy
import sys
from controller_2d import Controller
import threading
from controller_2d import Controller
import tkinter as tk
import rospy

class VelocityUI:


def __init__(self, init_vel: float, buggy_name: str):
self.buggy_vel = 0 # So the buggy doesn't start moving without user input
self.controller = Controller(buggy_name)
Expand All @@ -34,7 +32,7 @@ def step(self):
'''Update velocity of buggy'''
self.buggy_vel = self.scale.get()/10 # so we can set velocity with 0.1 precision
self.controller.set_velocity(self.buggy_vel)

if __name__ == "__main__":
rospy.init_node("velocity_ui")
init_vel = float(sys.argv[1])
Expand All @@ -43,4 +41,4 @@ def step(self):
rate = rospy.Rate(100)
while not rospy.is_shutdown():
vel.step()
rate.sleep()
rate.sleep()
12 changes: 5 additions & 7 deletions rb_ws/src/buggy/scripts/auton/autonsystem.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
#!/usr/bin/env python3

import sys

# ROS Message Imports
from std_msgs.msg import Float32, Float64, Bool
from nav_msgs.msg import Odometry
from threading import Lock

import numpy as np
from threading import Lock
import rospy

# ROS Message Imports
from std_msgs.msg import Float32, Float64, Bool
from nav_msgs.msg import Odometry

from trajectory import Trajectory
from world import World
Expand Down Expand Up @@ -50,7 +49,6 @@ def __init__(self, trajectory, controller, brake_controller, buggy_name, is_sim)
rospy.Subscriber(buggy_name + "/nav/odom", Odometry, self.update_msg)

rospy.Subscriber(buggy_name + "nav/odom", Odometry, self.update_msg)

self.covariance_warning_publisher = rospy.Publisher(
buggy_name + "/debug/is_high_covariance", Bool, queue_size=1
)
Expand Down Expand Up @@ -82,7 +80,7 @@ def update_speed(self, msg):
def update_msg(self, msg):
with self.lock:
self.msg = msg

def tick_caller(self):
while ((not rospy.is_shutdown()) and (self.msg == None)): # with no message, we wait
rospy.sleep(0.001)
Expand Down

0 comments on commit 507462b

Please sign in to comment.