Skip to content

Commit

Permalink
Merge branch 'ros-2-complete' of https://github.com/purdue-arc/rocket…
Browse files Browse the repository at this point in the history
…_league into ros-2-complete
  • Loading branch information
DinoSage committed Feb 25, 2024
2 parents a3eaaac + d4eb184 commit f66d673
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 32 deletions.
30 changes: 0 additions & 30 deletions src/rktl_autonomy/nodes/rocket_league_agent

This file was deleted.

35 changes: 35 additions & 0 deletions src/rktl_autonomy/rktl_autonomy/rocket_league_agent.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
#!/usr/bin/env python3
"""Real-time evaluation of the agent trained for the Rocket League project.
License:
BSD 3-Clause License
Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC)
All rights reserved.
"""

from rktl_autonomy.rocket_league_interface import RocketLeagueInterface
from stable_baselines3 import PPO
from os.path import expanduser
from rclpy.exceptions import ROSInterruptException


def main():
# create interface (and init ROS)
env = RocketLeagueInterface(eval=True)

# load the model
weights = expanduser(env.node.get_parameter('~weights').get_parameter_value().string_value)
model = PPO.load(weights)

# evaluate in real-time
obs = env.reset()
while True:
action, __ = model.predict(obs)
try:
obs, __, __, __ = env.step(action)
# except rospy.ROSInterruptException:
except ROSInterruptException:
exit()

if __name__=='__main__':
main()

2 changes: 1 addition & 1 deletion src/rktl_autonomy/rktl_autonomy/rocket_league_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

# ROS
import rclpy
from rclpy import Node
from rclpy.node import Node
from rclpy.parameter import Parameter
from nav_msgs.msg import Odometry
from rktl_msgs.msg import ControlCommand, MatchStatus
Expand Down
3 changes: 2 additions & 1 deletion src/rktl_autonomy/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
(os.path.join('lib', package_name), glob(os.path.join(package_name, '*.py'))),
],
install_requires=['setuptools'],
zip_safe=True,
Expand All @@ -23,7 +24,7 @@
tests_require=['pytest'],
entry_points={
'console_scripts': [

'rocket_league_agent = rktl_autonomy.rocket_league_agent:main'
],
},
)

0 comments on commit f66d673

Please sign in to comment.