1515from rclpy .node import Node
1616from rclpy .parameter import Parameter
1717from rclpy .qos import DurabilityPolicy , QoSProfile
18- from std_srvs .srv import Empty
19-
18+ from tf_transformations import euler_from_quaternion , quaternion_from_euler
2019
2120from bitbots_auto_test .monitoring_node import Monitoring
22- from bitbots_msgs .srv import SetObjectPose , SetObjectPosition
21+ from bitbots_msgs .srv import SetObjectPose , SetObjectPosition , SimulatorRecord
2322
2423
2524class TestResult :
@@ -82,23 +81,33 @@ def score(self):
8281 else :
8382 return self .judge ()
8483
85- def set_robot (self , x : float , y : float ):
84+ def set_robot (self , x : float , y : float , angle : float = 0.0 ):
8685 request = SetObjectPose .Request ()
8786 request .object_name = "amy"
8887 request .pose .position .x = x
8988 request .pose .position .y = y
9089 request .pose .position .z = 0.42
91- request .pose .orientation .x = 0.0
92- request .pose .orientation .y = 0.0
93- request .pose .orientation .z = 0.0
94- request .pose .orientation .w = 0.0
90+
91+ old_orientation = self .handle .robot_pose .orientation
92+ old_quat = [old_orientation .x , old_orientation .y , old_orientation .z , old_orientation .w ]
93+ try :
94+ old_roll , old_pitch , _old_yaw = euler_from_quaternion (old_quat )
95+ except ValueError :
96+ old_roll , old_pitch , _old_yaw = 0.0 , 0.0 , 0.0
97+
98+ x_q , y_q , z_q , w_q = quaternion_from_euler (old_roll , old_pitch , angle )
99+ request .pose .orientation .x = x_q
100+ request .pose .orientation .y = y_q
101+ request .pose .orientation .z = z_q
102+ request .pose .orientation .w = w_q
103+
95104 self .handle .set_robot_pose_service .call (request )
96105 if not self .handle .get_parameter ("fake_localization" ).value :
97106 rf = ResetFilter .Request ()
98107 rf .init_mode = ResetFilter .Request .POSE
99108 rf .x = x
100109 rf .y = y
101- rf .angle = 0.0
110+ rf .angle = angle
102111 self .handle .reset_localization .call (rf )
103112
104113 def set_ball (self , x : float , y : float ):
@@ -222,7 +231,7 @@ def __init__(self, monitoring_node: Monitoring):
222231
223232 self .set_robot_pose_service = self .create_client (SetObjectPose , "set_robot_pose" )
224233 self .set_ball_pos_service = self .create_client (SetObjectPosition , "set_ball_position" )
225- self .recording_service = self .create_client (Empty , "simulator_record" )
234+ self .recording_service = self .create_client (SimulatorRecord , "simulator_record" )
226235 self .create_subscription (ModelStates , "/model_states" , qos_profile = 10 , callback = self .model_states_callback )
227236 self .ball_pose = Pose ()
228237 self .ball_twist = Twist ()
@@ -274,15 +283,17 @@ def setup_sequence(self):
274283 gs_msg .header .stamp = self .get_clock ().now ().to_msg ()
275284 gs_msg .kicking_team = TEAM_ID
276285 gs_msg .main_state = 2 # 2=SET, force robot to stand still
286+ gs_msg .stopped = True
277287 self .gamestate_publisher .publish (gs_msg )
278288
279- self .get_clock ().sleep_for (Duration (seconds = 2 )) # Let robot react & simulation settle
289+ self .get_clock ().sleep_for (Duration (seconds = 3 )) # Let robot react & simulation settle
280290 self .current_test .setup () # Teleport robot
281291
282- self .get_clock ().sleep_for (Duration (seconds = 2 )) # Let simulation settle
292+ self .get_clock ().sleep_for (Duration (seconds = 3 )) # Let simulation settle
283293
284294 gs_msg .header .stamp = self .get_clock ().now ().to_msg ()
285295 gs_msg .main_state = 3 # 3=PLAYING, make robot play ball
296+ gs_msg .stopped = False
286297 self .gamestate_publisher .publish (gs_msg )
287298 self .current_test .start_recording ()
288299 self .monitoring_node .write_event (
@@ -317,8 +328,9 @@ def loop(self):
317328 while self .get_clock ().now () - start < Duration (seconds = 1 ):
318329 pass
319330 self .get_logger ().info ("Starting main loop" )
320- request = Empty .Request ()
321- self .recording_service .call (request ) # start
331+ request = SimulatorRecord .Request ()
332+ request .start = True
333+ self .recording_service .call (request ) # start
322334 self .next_test ()
323335 self .setup_sequence ()
324336 while True :
@@ -331,7 +343,9 @@ def loop(self):
331343 self .get_logger ().info ("Done with all tests" )
332344 break
333345 self .setup_sequence ()
334- self .recording_service .call (request ) # stop
346+ stop_request = SimulatorRecord .Request ()
347+ stop_request .stop = True
348+ self .recording_service .call (stop_request ) # stop
335349
336350
337351def main ():
0 commit comments