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
T3OTWAWKI committed Mar 2, 2024
2 parents 4f75ad7 + 35bbed2 commit d281027
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 18 deletions.
5 changes: 3 additions & 2 deletions src/rktl_game/launch/game.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import launch_ros.actions
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory
from launch.launch_description_sources import get_launch_description_from_any_launch_file


def generate_launch_description():
Expand All @@ -14,9 +15,9 @@ def generate_launch_description():
output='screen'
),
launch.actions.IncludeLaunchDescription(
PythonLaunchDescriptionSource(
launch.launch_description_sources.AnyLaunchDescriptionSource(
os.path.join(get_package_share_directory(
'rosbridge_server'), 'launch/rosbridge_websocket.launch.py')
'rosbridge_server'), 'launch/rosbridge_websocket_launch.xml')
)
)
])
Expand Down
5 changes: 2 additions & 3 deletions src/rktl_game/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
],
},
'console_scripts': [ ],
}
)
26 changes: 13 additions & 13 deletions src/rktl_sim/rktl_sim/vis_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
from nav_msgs.msg import Odometry
import rclpy
import sys
from rclpy.exceptions import ROSInterruptException

from rktl_dependencies.transformations import euler_from_quaternion

Expand Down Expand Up @@ -42,19 +43,18 @@ def __init__(self):
# goal_width = rospy.get_param('/field/goal/width')
# wall_thickness = rospy.get_param('/field/wall_thickness')
# ball_radius = rospy.get_param("/ball/radius")
field_width = node.declare_parameter('/field/width').value
field_length = node.declare_parameter('/field/length').value
goal_width = node.declare_parameter('/field/goal/width').value
wall_thickness = node.declare_parameter('/field/wall_thickness').value
ball_radius = node.declare_parameter("/ball/radius").value
field_width = node.declare_parameter('/field/width').get_parameter_value().double_value
field_length = node.declare_parameter('/field/length').get_parameter_value().double_value
goal_width = node.declare_parameter('/field/goal/width').get_parameter_value().double_value
wall_thickness = node.declare_parameter('/field/wall_thickness').get_parameter_value().double_value
ball_radius = node.declare_parameter("/ball/radius").get_parameter_value().double_value



# Creating pygame render

self.window = visualizer.Window(
field_width, field_length, wall_thickness,
# rospy.get_param('~window_name', 'Rocket League Visualizer'))
node.declare_parameter('~window_name', 'Rocket League Visualizer').value)

# Collecting private parameters
Expand All @@ -65,7 +65,7 @@ def __init__(self):
# car_length = rospy.get_param("~cars/body_length")
self.frame_id = node.declare_parameter("~frame_id", "map").value
self.timeout = node.declare_parameter("~timeout", 10).value
rate = rclpy.create_node('simple_node').create_rate((node.declare_parameter("~rate", 20).value))
rate = rclpy.create_node('simple_node').create_rate((node.declare_parameter("~rate", 20).get_parameter_value().double_value))
car_width = node.declare_parameter("~cars/body_width").value
car_length = node.declare_parameter("~cars/body_length").value

Expand Down Expand Up @@ -169,11 +169,11 @@ def __init__(self):
# rospy.Subscriber("/cars/car0/lookahead_pnt", Float32, self.lookahead_cb)
# rospy.Subscriber("/agents/agent0/bezier_path", BezierPathList, self.bezier_path_cb)

node.create_subscription(Odometry, "/ball/odom", self.ball_odom_cb)
node.create_subscription(Odometry, "/cars/car0/odom", self.car_odom_cb)
node.create_subscription(Path, "/cars/car0/path", self.path_arr_cb)
node.create_subscription(Float32, "/cars/car0/lookahead_pnt", self.lookahead_cb)
node.create_subscription(BezierPathList, "/agents/agent0/bezier_path", self.bezier_path_cb)
node.create_subscription(Odometry, "/ball/odom", self.ball_odom_cb, qos_profile=1)
node.create_subscription(Odometry, "/cars/car0/odom", self.car_odom_cb, qos_profile=1)
node.create_subscription(Path, "/cars/car0/path", self.path_arr_cb, qos_profile=1)
node.create_subscription(Float32, "/cars/car0/lookahead_pnt", self.lookahead_cb, qos_profile=1)
node.create_subscription(BezierPathList, "/agents/agent0/bezier_path", self.bezier_path_cb, qos_profile=1)


while not rclpy.ok():
Expand All @@ -183,7 +183,7 @@ def __init__(self):
exit()
try:
rate.sleep()
except rclpy.ROSInterruptException:
except ROSInterruptException:
pass


Expand Down

0 comments on commit d281027

Please sign in to comment.