Skip to content

Commit

Permalink
added command line args
Browse files Browse the repository at this point in the history
  • Loading branch information
TiaSinghania committed Oct 29, 2024
1 parent 97191d0 commit a62da31
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 7 deletions.
18 changes: 13 additions & 5 deletions rb_ws/src/buggy/buggy/simulator/engine.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ def __init__(self):
super().__init__('sim_single')
self.get_logger().info('INITIALIZED.')


self.starting_poses = {
"Hill1_NAND": (Simulator.UTM_EAST_ZERO + 0, Simulator.UTM_NORTH_ZERO + 0, -110),
"Hill1_SC": (Simulator.UTM_EAST_ZERO + 20, Simulator.UTM_NORTH_ZERO + 30, -110),
Expand Down Expand Up @@ -59,20 +60,27 @@ def __init__(self):
self.navsatfix_noisy_publisher = self.create_publisher(
NavSatFix, "state/pose_navsat_noisy", 1
)





self.declare_parameter('velocity', 12)
if (self.get_namespace() == "/SC"):
self.buggy_name = "SC"
init_pose = self.starting_poses["Hill1_SC"]
self.declare_parameter('pose', "Hill1_SC")
self.wheelbase = Simulator.WHEELBASE_SC

if (self.get_namespace() == "/NAND"):
self.buggy_name = "NAND"
init_pose = self.starting_poses["Hill1_NAND"]
self.declare_parameter('pose', "Hill1_NAND")
self.wheelbase = Simulator.WHEELBASE_NAND

self.velocity = self.get_parameter("velocity").value
init_pose_name = self.get_parameter("pose").value
self.init_pose = self.starting_poses[init_pose_name]

self.e_utm, self.n_utm, self.heading = init_pose
# TODO: do we want to not hard code this
self.velocity = 12 # m/s
self.e_utm, self.n_utm, self.heading = self.init_pose
self.steering_angle = 0 # degrees
self.rate = 200 # Hz
self.pub_skip = 2 # publish every pub_skip ticks
Expand Down
11 changes: 9 additions & 2 deletions rb_ws/src/buggy/launch/sim_2d_single.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,15 @@
<launch>

<node pkg="foxglove_bridge" exec="foxglove_bridge" name="foxglove" namespace="SC"/>
<node pkg="buggy" exec="hello_world" name="hello_world" namespace="SC" />
<node pkg="buggy" exec="sim_single" name="SC_sim_single" namespace="SC"/>
<node pkg="buggy" exec="sim_single" name="NAND_sim_single" namespace="NAND"/>
<node pkg="buggy" exec="sim_single" name="SC_sim_single" namespace="SC">
<param name="velocity" value="12"/>
<param name="pose" value="Hill1_SC"/>
</node>
<node pkg="buggy" exec="sim_single" name="NAND_sim_single" namespace="NAND">
<param name="velocity" value="12"/>
<param name="pose" value="Hill1_NAND"/>
</node>

<!-- <node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />
<node name="hello_world" pkg="buggy" type="hello_world" /> -->
Expand Down

0 comments on commit a62da31

Please sign in to comment.