Skip to content

Commit

Permalink
Merge branch 'ros-2-complete' of github.com:purdue-arc/rocket_league …
Browse files Browse the repository at this point in the history
…into ros-2-complete
  • Loading branch information
rtjord committed Mar 2, 2024
2 parents e13b3ca + 101b08d commit f5c4e09
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 11 deletions.
4 changes: 2 additions & 2 deletions src/rktl_autonomy/test/test_step_node
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ import unittest, rostest, rclpy
from rclpy.duration import Duration
from nav_msgs.msg import Odometry
from rktl_msgs.msg import MatchStatus
from std_srvs.srv import Empty, EmptyResponse
from std_srvs.srv import Empty, Empty_Response
from rosgraph_msgs.msg import Clock
import numpy as np
from rktl_autonomy.rocket_league_interface import RocketLeagueInterface
Expand Down Expand Up @@ -164,7 +164,7 @@ class TestStep(unittest.TestCase):
def reset(self, __):
"""Do nothing."""
self.assertTrue(self.want_reset, msg='env reset called when unexpected')
return EmptyResponse()
return Empty_Response()

if __name__ == '__main__':
rostest.rosrun('rktl_autonomy', 'test_rktl_rewards', TestStep)
8 changes: 4 additions & 4 deletions src/rktl_game/rktl_game/nodes/game_manager
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ import rclpy
from std_msgs.msg import Bool, Header
from nav_msgs.msg import Odometry
from rktl_msgs.msg import Score, MatchStatus
from std_srvs.srv import Empty, EmptyResponse
from std_srvs.srv import Empty, Empty_Response

class ScoreKeeper():
def __init__(self):
Expand Down Expand Up @@ -71,7 +71,7 @@ class ScoreKeeper():
self.enabled = False
self.match_status = 0
self.active_pub.publish(False)
return EmptyResponse()
return Empty_Response()

def reset(self, _):
self.orange_score = 0
Expand All @@ -83,13 +83,13 @@ class ScoreKeeper():
header = Header()
header.stamp = node.get_clock().now()
self.match_status_pub.publish(MatchStatus(header, 0, self.game_clock, Score(0, 0)))
return EmptyResponse()
return Empty_Response()

def unpause(self, _):
self.enabled = True
self.match_status = 1
self.active_pub.publish(True)
return EmptyResponse()
return Empty_Response()

def check_goal(self, ball_pose: Odometry):
if self.enabled:
Expand Down
1 change: 1 addition & 0 deletions src/rktl_game/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
tests_require=['pytest'],
entry_points={
'console_scripts': [
'game_manager = rktl_game.node.game_manager:main'
],
},
)
4 changes: 2 additions & 2 deletions src/rktl_planner/rktl_planner/nodes/path_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ def car_odom_cb(self, data: Odometry):
def ball_odom_cb(self, data: Odometry):
self.ball_odom = data

def reset(self, _: EmptyRequest):
def reset(self, _: Empty_Request):
req = self.path_req(self.car_odom, self.ball_odom, self.goal_pos)
res = self.path_client(req)
if self.linear_path_pub:
Expand All @@ -146,7 +146,7 @@ def reset(self, _: EmptyRequest):
bezier_path_list = BezierPathList()
bezier_path_list.paths = res.bezier_paths
self.bezier_path_pub.publish(bezier_path_list)
return EmptyResponse()
return Empty_Response()

if __name__ == '__main__':
PathPlanner()
6 changes: 3 additions & 3 deletions src/rktl_sim/rktl_sim/nodes/simulator
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ import time

#import rospy

from std_srvs.srv import Empty, EmptyResponse
from std_srvs.srv import Empty, Empty_Response
from threading import Lock
from enum import Enum

Expand Down Expand Up @@ -171,7 +171,7 @@ class Simulator(object):

self.last_time = None
self.reset_lock.release()
return EmptyResponse()
return Empty_Response()

def reset_ball_cb(self, _):
"""Resets the ball sensor noise and pose WITHOUT resetting the whole sim."""
Expand All @@ -183,7 +183,7 @@ class Simulator(object):
self.ball_init_speed = self.get_sim_param('/ball/init_speed')

self.sim.reset_ball()
return EmptyResponse()
return Empty_Response()

def loop_once(self):
"""Step the simulation once step, updating match status, moving and publishing new car and ball positions."""
Expand Down

0 comments on commit f5c4e09

Please sign in to comment.