Skip to content

Commit

Permalink
Fixed change
Browse files Browse the repository at this point in the history
  • Loading branch information
mehulgoel873 committed Apr 3, 2024
1 parent c3420dd commit a6b9c7c
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 3 deletions.
2 changes: 1 addition & 1 deletion rb_ws/src/buggy/launch/nand-system.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

<launch>

<node name="bnyahaj" pkg="buggy" type="ros_to_bnyahaj.py" output="screen" args="--self_name NAND --other_name SC --teensy_name nand-teensy"/>
<node name="bnyahaj" pkg="buggy" type="ros_to_bnyahaj.py" output="screen" args="--self_name NAND --teensy_name nand-teensy"/>

<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />
<node name="telematics" pkg="buggy" type="telematics.py" />
Expand Down
8 changes: 6 additions & 2 deletions rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,11 @@ def __init__(self, self_name, other_name, teensy_name):
rospy.Subscriber(self_name + "/buggy/input/steering", Float64, self.set_steering)
rospy.Subscriber(self_name + "/debug/sanity_warning", Int8, self.set_alarm)

self.odom_publisher = rospy.Publisher(other_name + "/nav/odom", ROSOdom, queue_size=1)

if other_name is None:
self.odom_publisher = rospy.Publisher(self_name + "/nav/odom", ROSOdom, queue_size=1)
else:
self.odom_publisher = rospy.Publisher(other_name + "/nav/odom", ROSOdom, queue_size=1)
# upper bound of steering update rate, make sure auton sends slower than this
self.steer_send_rate = rospy.Rate(500)
self.read_rate = rospy.Rate(1000)
Expand Down Expand Up @@ -114,7 +118,7 @@ def loop(self):
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("--self_name", type=str, help="name of ego-buggy", required=True)
parser.add_argument("--other_name", type=str, help="name of other buggy", required=True)
parser.add_argument("--other_name", type=str, help="name of other buggy", required=False, default=None)
parser.add_argument("--teensy_name", type=str, help="name of teensy port", required=True)
args, _ = parser.parse_known_args()
self_name = args.self_name
Expand Down

0 comments on commit a6b9c7c

Please sign in to comment.