Skip to content

Commit

Permalink
fixed sim_single
Browse files Browse the repository at this point in the history
  • Loading branch information
mehulgoel873 committed Jul 15, 2024
1 parent b2e4354 commit 9b55a22
Show file tree
Hide file tree
Showing 7 changed files with 49 additions and 76 deletions.
15 changes: 15 additions & 0 deletions rb_ws/src/buggy/config/sim_single.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
start_pos: "Hill1_SC"
velocity: 15.0
buggy_name: "SC"

manual_vel: false
auto_vel: false


# Auton Arguments
controller: "stanley"
dist: 0.0
traj: "buggycourse_safe.json"
self_name: "SC"
other_name: NONE

17 changes: 6 additions & 11 deletions rb_ws/src/buggy/launch/sim_single.launch
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
<launch>
<arg name="start_pos" default="Hill1_SC" />
<arg name="autonsystem_args" default="--controller stanley --dist 0.0 --traj buggycourse_safe.json --self_name SC" />
<arg name="velocity" default="15.0" />
<arg name="buggy_name" default="SC" />
<rosparam file="src/buggy/config/sim_single.yaml" />

<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />

Expand All @@ -12,21 +9,19 @@
<group if="$(arg auto_vel)">
<!-- Run the auto velocity updater -->
<node name="sc_vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg velocity) SC"/>
output="screen"/>
</group>

<group if="$(arg manual_vel)">
<!-- Run the manual velocity updater -->
<node name="sc_velocity_ui" pkg="buggy" type="velocity_ui.py"
output="screen" args="$(arg velocity) SC"/>
output="screen"/>
</group>

<node name="sim_2d_engine" pkg="buggy" type="engine.py" output="screen"
args="$(arg start_pos) $(arg velocity) $(arg buggy_name)"/>
<node name="sim_2d_engine" pkg="buggy" type="engine.py" output="screen"/>

<node name="auton_system" pkg="buggy" type="autonsystem.py" output="screen"
args="$(arg autonsystem_args)"/>
<node name="auton_system" pkg="buggy" type="autonsystem.py" output="screen"/>

<node name="rolling_sanity_check" pkg="buggy" type="rolling_sanity_check.py" output="screen" args="$(arg buggy_name)"/>
<node name="rolling_sanity_check" pkg="buggy" type="rolling_sanity_check.py" output="screen" args=""/>

</launch>
6 changes: 3 additions & 3 deletions rb_ws/src/buggy/scripts/2d_sim/engine.py
Original file line number Diff line number Diff line change
Expand Up @@ -332,9 +332,9 @@ def loop(self):
print("sim 2d eng args:")
print(sys.argv)

start_pos = sys.argv[1]
velocity = float(sys.argv[2])
buggy_name = sys.argv[3]
start_pos = rospy.get_param("/start_pos")
velocity = float(rospy.get_param("/velocity"))
buggy_name = rospy.get_param("/buggy_name")

sim = Simulator(start_pos, velocity, buggy_name)
for i in range(100):
Expand Down
4 changes: 2 additions & 2 deletions rb_ws/src/buggy/scripts/2d_sim/velocity_ui.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@ def step(self):

if __name__ == "__main__":
rospy.init_node("velocity_ui")
init_vel = float(sys.argv[1])
buggy_name = sys.argv[2]
init_vel = float(rospy.get_param("/velocity"))
buggy_name = rospy.get_param("/SC")
vel = VelocityUI(init_vel, buggy_name)
rate = rospy.Rate(100)
while not rospy.is_shutdown():
Expand Down
4 changes: 2 additions & 2 deletions rb_ws/src/buggy/scripts/2d_sim/velocity_updater.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,8 @@ def step(self):
if __name__ == "__main__":
rospy.init_node("vel_updater")

init_vel = float(sys.argv[1])
buggy_name = sys.argv[2]
init_vel = float(rospy.get_param("/velocity"))
buggy_name = rospy.get_param("/SC")
vel = VelocityUpdater(init_vel, buggy_name)
rate = rospy.Rate(vel.RATE)

Expand Down
77 changes: 20 additions & 57 deletions rb_ws/src/buggy/scripts/auton/autonsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -261,65 +261,28 @@ def planner_tick(self):
# update local trajectory via path planner
self.path_planner.compute_traj(self_pose, other_pose)

def init_parser ():
"""
Returns a parser to read launch file arguments to AutonSystem.
"""
parser = argparse.ArgumentParser()
parser.add_argument("--controller",
type=str,
help="set controller type",
required=True)

parser.add_argument(
"--dist",
type=float,
help="start buggy at meters distance along the path",
required=True)

parser.add_argument(
"--traj",
type=str,
help="path to the trajectory file, relative to /rb_ws/src/buggy/paths/",
required=True)

parser.add_argument(
"--self_name",
type=str,
help="name of ego-buggy",
required=True)

parser.add_argument(
"--left_curb",
type=str,
help="Path of curb data, relative to /rb_ws/src/buggy/paths/",
default=""
, required=False)

parser.add_argument(
"--other_name",
type=str,
help="name of other buggy, if left unspecified, the autonsystem assumes it is the only buggy on the course",
required=False)

parser.add_argument(
"--profile",
action='store_true',
help="turn on profiling for the path planner")
return parser

if __name__ == "__main__":
rospy.init_node("auton_system")
parser = init_parser()

args, _ = parser.parse_known_args()
ctrl = args.controller
start_dist = args.dist
traj = args.traj
self_name = args.self_name
other_name = args.other_name
profile = args.profile
left_curb_file = args.left_curb

ctrl = rospy.get_param("/controller")
start_dist = rospy.get_param("/dist")
traj = rospy.get_param("/traj")
self_name = rospy.get_param("/self_name")

if rospy.has_param("/other_name"):
other_name = rospy.get_param("/other_name")
else:
other_name = None

if rospy.has_param("/profile"):
profile = rospy.get_param("/profile")
else:
profile = None

if rospy.has_param("/left_curb"):
left_curb_file = rospy.get_param("/left_curb")
else:
left_curb_file = ""

rospy.loginfo("\n\nStarting Controller: " + str(ctrl) + "\n\n")
rospy.loginfo("\n\nUsing path: /rb_ws/src/buggy/paths/" + str(traj) + "\n\n")
Expand Down
2 changes: 1 addition & 1 deletion rb_ws/src/buggy/scripts/auton/rolling_sanity_check.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ def sanity_check(self):

if __name__ == "__main__":
rospy.init_node("rolling_sanity_check")
check = SanityCheck(sys.argv[1])
check = SanityCheck(rospy.get_param("/buggy_name"))
rate = rospy.Rate(100)

while not rospy.is_shutdown():
Expand Down

0 comments on commit 9b55a22

Please sign in to comment.