From 87a8e0dd7afddc5db81aab6c7da4630e94a2a0da Mon Sep 17 00:00:00 2001 From: Adarsh Veerapaneni Date: Sat, 2 Mar 2024 21:17:16 +0000 Subject: [PATCH 1/2] fixed EmptyRequest and EmptyResponse in rktl_planner --- src/rktl_planner/rktl_planner/nodes/path_planner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rktl_planner/rktl_planner/nodes/path_planner.py b/src/rktl_planner/rktl_planner/nodes/path_planner.py index 819088d3..28c6772e 100755 --- a/src/rktl_planner/rktl_planner/nodes/path_planner.py +++ b/src/rktl_planner/rktl_planner/nodes/path_planner.py @@ -8,7 +8,7 @@ from nav_msgs.msg import Odometry from geometry_msgs.msg import Pose from rktl_msgs.msg import BezierPathList, Path -from std_srvs.srv import Empty, EmptyRequest, EmptyResponse +from std_srvs.srv import Empty, Empty_Request, Empty_Response from rktl_planner.srv import CreateBezierPath, CreateBezierPathRequest def create_simple_path_req(car_odom, ball_odom, goal_pos): From a215ead89e9935b44238dac788e0de9f7bbaf113 Mon Sep 17 00:00:00 2001 From: jcrm1 <52137472+jcrm1@users.noreply.github.com> Date: Sat, 2 Mar 2024 21:23:18 +0000 Subject: [PATCH 2/2] Import errors: Empty_Response and Empty_Request --- src/rktl_autonomy/test/test_step_node | 4 ++-- src/rktl_game/rktl_game/nodes/game_manager | 8 ++++---- src/rktl_planner/rktl_planner/nodes/path_planner.py | 4 ++-- src/rktl_sim/rktl_sim/nodes/simulator | 6 +++--- 4 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/rktl_autonomy/test/test_step_node b/src/rktl_autonomy/test/test_step_node index f8b89359..22711c0c 100755 --- a/src/rktl_autonomy/test/test_step_node +++ b/src/rktl_autonomy/test/test_step_node @@ -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 @@ -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) \ No newline at end of file diff --git a/src/rktl_game/rktl_game/nodes/game_manager b/src/rktl_game/rktl_game/nodes/game_manager index 6cb07e10..d83c37fb 100755 --- a/src/rktl_game/rktl_game/nodes/game_manager +++ b/src/rktl_game/rktl_game/nodes/game_manager @@ -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): @@ -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 @@ -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: diff --git a/src/rktl_planner/rktl_planner/nodes/path_planner.py b/src/rktl_planner/rktl_planner/nodes/path_planner.py index 28c6772e..96242a69 100755 --- a/src/rktl_planner/rktl_planner/nodes/path_planner.py +++ b/src/rktl_planner/rktl_planner/nodes/path_planner.py @@ -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: @@ -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() diff --git a/src/rktl_sim/rktl_sim/nodes/simulator b/src/rktl_sim/rktl_sim/nodes/simulator index eca0d8b0..cac5f39d 100755 --- a/src/rktl_sim/rktl_sim/nodes/simulator +++ b/src/rktl_sim/rktl_sim/nodes/simulator @@ -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 @@ -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.""" @@ -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."""