diff --git a/smach_ros/test/introspection_test.py b/smach_ros/test/introspection_test.py index 7acc7ee..8ad5789 100755 --- a/smach_ros/test/introspection_test.py +++ b/smach_ros/test/introspection_test.py @@ -41,8 +41,6 @@ def test_introspection(self): node = rclpy.create_node("sm_node") node.get_logger().set_level(rclpy.logging.LoggingSeverity.DEBUG) executor = SingleThreadedExecutor() - def spin(): - rclpy.spin(node, executor=executor) # Construct state machine sm = StateMachine(['done']) @@ -67,13 +65,22 @@ def spin(): # Run introspector intro_server = IntrospectionServer('intro_test', sm, '/intro_test') intro_server.get_logger().set_level(rclpy.logging.LoggingSeverity.DEBUG) - server_thread = threading.Thread(target=intro_server.start) - server_thread.start() + intro_server.start() intro_client = IntrospectionClient() intro_client.get_logger().set_level(rclpy.logging.LoggingSeverity.DEBUG) servers = intro_client.get_servers() + executor.add_node(node) + executor.add_node(intro_server) + executor.add_node(intro_client) + + def spin(executor): + executor.spin() + + spinner = threading.Thread(target=spin, args=(executor,)) + spinner.start() + rate = intro_client.create_rate(10) while '/intro_test' not in servers and rclpy.ok(): servers = intro_client.get_servers() @@ -93,9 +100,6 @@ def spin(): assert init_set - spinner = threading.Thread(target=spin) - spinner.start() - outcome = sm.execute() assert outcome == 'done'