@@ -120,18 +120,30 @@ def setUp(self):
120120 self .assertTrue (self ._io_status_controller_interface .resend_robot_program ().success )
121121 self .tf_buffer = Buffer ()
122122 self .tf_listener = TransformListener (self .tf_buffer , self .node )
123-
124- def lookup_tcp_in_base (self , tf_prefix , timepoint ):
125- trans = None
126- while not trans :
127- rclpy .spin_once (self .node )
123+ time .sleep (1 ) # Wait whether the controller stopper resets controllers
124+
125+ def wait_for_lookup (self , source , target , timepoint , timeout = 5.0 ):
126+ """
127+ Wait until the transform between source and target is available.
128+
129+ :param source: The source frame
130+ :param target: The target frame
131+ :param timeout: The point in time at which to make the lookup
132+ :param timeout: Timeout in seconds
133+ :return: transform between source and target at the given timepoint
134+ :raises TimeoutError: If the transform is not available within the timeout
135+ """
136+ end_time = time .time () + timeout
137+ while time .time () < end_time :
128138 try :
129- trans = self .tf_buffer .lookup_transform (
130- tf_prefix + "base" , tf_prefix + "tool0" , timepoint
131- )
139+ trans = self .tf_buffer .lookup_transform (source , target , timepoint )
140+ return trans
132141 except TransformException :
133- pass
134- return trans
142+ rclpy .spin_once (self .node )
143+ raise TimeoutError ()
144+
145+ def lookup_tcp_in_base (self , tf_prefix , timepoint ):
146+ return self .wait_for_lookup (tf_prefix + "base" , tf_prefix + "tool0_controller" , timepoint )
135147
136148 # Implementation of force mode test to be reused
137149 # todo: If we move to pytest this could be done using parametrization
@@ -201,6 +213,9 @@ def run_force_mode(self, tf_prefix):
201213 ),
202214 header = trans_after .header ,
203215 )
216+ self .wait_for_lookup (
217+ diff .header .frame_id , tf_prefix + "tool0_controller" , diff .header .stamp
218+ )
204219 diff_in_tool0_controller = self .tf_buffer .transform (
205220 diff ,
206221 tf_prefix + "tool0_controller" ,
@@ -519,7 +534,6 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
519534 ],
520535 ).ok
521536 )
522- self ._force_mode_controller_interface = ForceModeInterface (self .node )
523537
524538 time .sleep (0.5 )
525539 trans_before_wait = self .lookup_tcp_in_base (tf_prefix , self .node .get_clock ().now ())
@@ -529,7 +543,10 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
529543 trans_after_wait = self .lookup_tcp_in_base (tf_prefix , self .node .get_clock ().now ())
530544
531545 self .assertAlmostEqual (
532- trans_before_wait .transform .translation .z , trans_after_wait .transform .translation .z
546+ trans_before_wait .transform .translation .z ,
547+ trans_after_wait .transform .translation .z ,
548+ delta = 1e-7 ,
549+ msg = "Robot should not move after force mode is stopped" ,
533550 )
534551
535552 def test_params_out_of_range_fails (self , tf_prefix ):
0 commit comments