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
sixfootsix50 committed Mar 2, 2024
2 parents 449abab + 475a98d commit d770223
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 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 @@ -64,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 @@ -182,7 +183,7 @@ def __init__(self):
exit()
try:
rate.sleep()
except rclpy.ROSInterruptException:
except ROSInterruptException:
pass


Expand Down

0 comments on commit d770223

Please sign in to comment.