Skip to content

Commit 3cbd9ff

Browse files
author
Antonio Loquercio
authored
Merge pull request #75 from tongtybj/PR/competition
Improve the competition evaluation process
2 parents 410ddf0 + b181e24 commit 3cbd9ff

File tree

2 files changed

+5
-6
lines changed

2 files changed

+5
-6
lines changed

envtest/ros/run_competition.py

+4-5
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,9 @@ def __init__(self, vision_based=False, ppo_path=None):
2121
rospy.init_node('agile_pilot_node', anonymous=False)
2222

2323
self.vision_based = vision_based
24-
self.ppo_path = ppo_path
24+
self.rl_policy = None
25+
if ppo_path is not None:
26+
self.rl_policy = load_rl_policy(ppo_path)
2527
self.publish_commands = False
2628
self.cv_bridge = CvBridge()
2729
self.state = None
@@ -64,10 +66,7 @@ def obstacle_callback(self, obs_data):
6466
return
6567
if self.state is None:
6668
return
67-
rl_policy = None
68-
if self.ppo_path is not None:
69-
rl_policy = load_rl_policy(self.ppo_path)
70-
command = compute_command_state_based(state=self.state, obstacles=obs_data, rl_policy=rl_policy)
69+
command = compute_command_state_based(state=self.state, obstacles=obs_data, rl_policy=self.rl_policy)
7170
self.publish_command(command)
7271

7372
def publish_command(self, command):

launch_evaluation.bash

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ do
4949

5050
cd -
5151

52-
sleep 0.5
52+
sleep 2.0
5353
rostopic pub /kingfisher/start_navigation std_msgs/Empty "{}" --once
5454

5555
# Wait until the evaluation script has finished

0 commit comments

Comments
 (0)