Skip to content

Commit

Permalink
added namespace config to debug steer
Browse files Browse the repository at this point in the history
  • Loading branch information
Jackack committed Apr 4, 2024
1 parent f7b8c00 commit e10183d
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 5 deletions.
3 changes: 1 addition & 2 deletions rb_ws/src/buggy/launch/debug_steer.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
<!-- roslaunch buggy debug_steer.launch -->

<launch>
<node name="debug_steer" pkg="buggy" type="debug_steer.py" output="screen"/>

<node name="debug_steer" pkg="buggy" type="debug_steer.py" output="screen" args="--self_name NAND"/>
</launch>
11 changes: 8 additions & 3 deletions rb_ws/src/buggy/scripts/debug/debug_steer.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#!/usr/bin/env python3
import argparse

import rospy
from std_msgs.msg import Float64
Expand All @@ -12,9 +13,9 @@ class DebugController():
Sends oscillating steering command for firmware debug
"""

def __init__(self) -> None:
def __init__(self, self_name) -> None:
self.steer_publisher = rospy.Publisher(
"SC/buggy/input/steering", Float64, queue_size=1)
self_name + "/buggy/input/steering", Float64, queue_size=1)
self.rate = 1000

def sin_steer(self, tick_count):
Expand Down Expand Up @@ -42,6 +43,10 @@ def loop(self):
rate.sleep()

if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("--self_name", type=str, help="name of ego-buggy", required=True)
args, _ = parser.parse_known_args()

rospy.init_node("debug_steer")
d = DebugController()
d = DebugController(args.self_name)
d.loop()

0 comments on commit e10183d

Please sign in to comment.