Skip to content

Commit

Permalink
refactor the policy load rule for evaluation code
Browse files Browse the repository at this point in the history
  • Loading branch information
tongtybj committed May 14, 2022
1 parent 410ddf0 commit 33ced4a
Showing 1 changed file with 4 additions and 5 deletions.
9 changes: 4 additions & 5 deletions envtest/ros/run_competition.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@ def __init__(self, vision_based=False, ppo_path=None):
rospy.init_node('agile_pilot_node', anonymous=False)

self.vision_based = vision_based
self.ppo_path = ppo_path
self.rl_policy = None
if ppo_path is not None:
self.rl_policy = load_rl_policy(ppo_path)
self.publish_commands = False
self.cv_bridge = CvBridge()
self.state = None
Expand Down Expand Up @@ -64,10 +66,7 @@ def obstacle_callback(self, obs_data):
return
if self.state is None:
return
rl_policy = None
if self.ppo_path is not None:
rl_policy = load_rl_policy(self.ppo_path)
command = compute_command_state_based(state=self.state, obstacles=obs_data, rl_policy=rl_policy)
command = compute_command_state_based(state=self.state, obstacles=obs_data, rl_policy=self.rl_policy)
self.publish_command(command)

def publish_command(self, command):
Expand Down

0 comments on commit 33ced4a

Please sign in to comment.