Skip to content

Commit

Permalink
fixed docs
Browse files Browse the repository at this point in the history
  • Loading branch information
TiaSinghania committed Jul 15, 2024
1 parent 32a4f4f commit 16e7b4d
Showing 1 changed file with 6 additions and 7 deletions.
13 changes: 6 additions & 7 deletions rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,9 @@ class Translator:
BnyaTelemetry: NAND's representation of NAND's odometry. Much more complete, used to translate between NAND's UKF implementation to NAND's ROS
Tuple
Tuple: sends other debug data
Performs reading (from Bnya Serial) and writing (from Ros Topics) on different python threads, so
be careful of multithreading synchronizaiton issues.
Performs reading (from Bnya Serial) and writing (from Ros Topics) on different python threads, so be careful of multithreading synchronizaiton issues.
SC:
(ROS) Self Steering topic --> (Bnyahaj) Stepper Motor
Expand All @@ -50,7 +49,8 @@ def __init__(self, self_name, other_name, teensy_name):
Initializes the subscribers, rates, and ros topics (including debug topics)
"""
self_name = self_name.upper()

if (other_name != None):
other_name = other_name.upper()

self.comms = Comms("/dev/" + teensy_name)
self.steer_angle = 0
Expand Down Expand Up @@ -117,7 +117,7 @@ def set_alarm(self, msg):

def set_steering(self, msg):
"""
Steering Angle Updater, updates the steering angle locally if updated on ros stopic
Steering Angle Updater, updates the steering angle locally if updated on ros topic
"""
rospy.loginfo(f"Read steering angle of: {msg.data}")
# print("Steering angle: " + str(msg.data))
Expand All @@ -128,7 +128,7 @@ def set_steering(self, msg):

def writer_thread(self):
"""
Sends ROS Topics to bnayhaj serial, only sends a steering angle when we receive a fresh one
Sends ROS Topics to bnyahaj serial, only sends a steering angle when we receive a fresh one
Will send steering and alarm node.
TODO: Does alarm node exist for NAND?
"""
Expand All @@ -149,7 +149,6 @@ def reader_thread(self):
Reads three different types of packets, that should have better ways of differntiating
Odometry -> (SC) NAND Odomotery
BnyaTelemetry -> (NAND) Self Odom
# also what if we want to send multiple tuples
tuple -> (SC, maybe NAND?) Debug Info
"""
rospy.loginfo("Starting reading odom from teensy!")
Expand Down

0 comments on commit 16e7b4d

Please sign in to comment.