diff --git a/src/rktl_launch/launch/rocket_league.launch.py b/src/rktl_launch/launch/rocket_league.launch.py index a7261f33..bf526086 100644 --- a/src/rktl_launch/launch/rocket_league.launch.py +++ b/src/rktl_launch/launch/rocket_league.launch.py @@ -25,8 +25,8 @@ def generate_launch_description(): package='rqt_gui', executable='rqt_gui', name='rqt_gui', - arguments='--perspective-file ' + os.path.join(get_package_share_directory( - 'rktl_launch'), 'rqt','rktl.perspective') + arguments=['--perspective-file', os.path.join(get_package_share_directory( + 'rktl_launch'), 'rqt','rktl.perspective')] ), launch_ros.actions.SetParametersFromFile( filename=os.path.join(get_package_share_directory( diff --git a/src/rktl_launch/launch/rocket_league_sim.launch.py b/src/rktl_launch/launch/rocket_league_sim.launch.py index de6fdbd1..742a0dd4 100644 --- a/src/rktl_launch/launch/rocket_league_sim.launch.py +++ b/src/rktl_launch/launch/rocket_league_sim.launch.py @@ -84,7 +84,7 @@ def generate_launch_description(): executable='rqt_gui', name='rqt_gui', condition=launch.conditions.LaunchConfigurationEquals('render', 'true'), - arguments=['--perspective-file ' + os.path.join(get_package_share_directory( + arguments=['--perspective-file', os.path.join(get_package_share_directory( 'rktl_launch'), 'rqt','rktl.perspective')] ), launch.actions.IncludeLaunchDescription( diff --git a/src/rktl_sim/rktl_sim/sim_simulator.py b/src/rktl_sim/rktl_sim/sim_simulator.py index 71b20de2..aebc9701 100755 --- a/src/rktl_sim/rktl_sim/sim_simulator.py +++ b/src/rktl_sim/rktl_sim/sim_simulator.py @@ -17,13 +17,12 @@ #import rospy -from std_srvs.srv import Empty, EmptyResponse +from std_srvs.srv import Empty, Empty_Response # might not need Empty_Response from threading import Lock from enum import Enum # local libraries -from rktl_sim.nodes import simulator from rktl_msgs.msg import MatchStatus, ControlCommand, ControlEffort @@ -171,7 +170,7 @@ def reset_cb(self, _): self.last_time = None self.reset_lock.release() - return EmptyResponse() + return Empty_Response() # might be Empty() def reset_ball_cb(self, _): """Resets the ball sensor noise and pose WITHOUT resetting the whole sim.""" @@ -183,7 +182,7 @@ def reset_ball_cb(self, _): self.ball_init_speed = self.get_sim_param('/ball/init_speed') self.sim.reset_ball() - return EmptyResponse() + return Empty_Response() # might be Empty() def loop_once(self): """Step the simulation once step, updating match status, moving and publishing new car and ball positions.""" diff --git a/src/rktl_sim/rktl_sim/vis_visualizer.py b/src/rktl_sim/rktl_sim/vis_visualizer.py index ff85b7cf..41c7cb19 100755 --- a/src/rktl_sim/rktl_sim/vis_visualizer.py +++ b/src/rktl_sim/rktl_sim/vis_visualizer.py @@ -23,7 +23,6 @@ # Local library -from rktl_sim.nodes import visualizer from rktl_msgs.msg import Path, BezierPathList from rktl_planner import BezierPath