77import rclpy
88import rclpy .executors
99from bitbots_localization .srv import ResetFilter
10- from game_controller_hl_interfaces .msg import GameState
10+ from game_controller_hsl_interfaces .msg import GameState
1111from gazebo_msgs .msg import ModelStates
1212from geometry_msgs .msg import Pose , Twist
1313from rclpy .clock import Duration
@@ -269,8 +269,8 @@ def setup_sequence(self):
269269 logger .info (f"Starting Test: id={ self .current_test .test_id } name={ self .current_test .__class__ .__name__ } " )
270270 gs_msg = GameState ()
271271 gs_msg .header .stamp = self .get_clock ().now ().to_msg ()
272- gs_msg .secondary_state_team = TEAM_ID
273- gs_msg .game_state = 2 # 2=SET, force robot to stand still
272+ gs_msg .kicking_team = TEAM_ID
273+ gs_msg .main_state = 2 # 2=SET, force robot to stand still
274274 self .gamestate_publisher .publish (gs_msg )
275275
276276 self .get_clock ().sleep_for (Duration (seconds = 2 )) # Let robot react & simulation settle
@@ -279,7 +279,7 @@ def setup_sequence(self):
279279 self .get_clock ().sleep_for (Duration (seconds = 2 )) # Let simulation settle
280280
281281 gs_msg .header .stamp = self .get_clock ().now ().to_msg ()
282- gs_msg .game_state = 3 # 3=PLAYING, make robot play ball
282+ gs_msg .main_state = 3 # 3=PLAYING, make robot play ball
283283 self .gamestate_publisher .publish (gs_msg )
284284 self .current_test .start_recording ()
285285 self .monitoring_node .write_event (
0 commit comments