ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

[ros2] Test is not finishing its execution

asked 2022-07-28 01:41:09 -0600

ravijoshi gravatar image

updated 2022-08-20 03:34:33 -0600

I am writing integration test cases for my ROS service. Please see the sample code snippet below:

#!/usr/bin/env python
# -*- coding: utf-8 -*-

from threading import Thread
import unittest

from example_interfaces.srv import AddTwoInts
import launch
import launch_ros
import launch_ros.actions
import launch_testing.actions
import pytest
import rclpy


@pytest.mark.rostest
def generate_test_description():
    minimal_service_node = launch_ros.actions.Node(
        package='examples_rclpy_minimal_service',
        namespace='',
        executable='service_member_function',
    )
    return (
        launch.LaunchDescription(
            [
                minimal_service_node,
                launch_testing.actions.ReadyToTest(),
            ]
        ),
        {
            'minimal_service': minimal_service_node,
        },
    )


class TestMinimalService(unittest.TestCase):

    @classmethod
    def setUpClass(cls):
        rclpy.init()

    @classmethod
    def tearDownClass(cls):
        rclpy.shutdown()

    def setUp(self):
        self.node = rclpy.create_node('test_minimal_service')
        self.client_add_two_ints = self.node.create_client(AddTwoInts, '/add_two_ints')
        # test cases work when the following line is uncommented
        # self.assertTrue(self.client_add_two_ints.wait_for_service(timeout_sec=5.0))

        self.spin_thread = Thread(target=rclpy.spin, args=(self.node,))
        self.spin_thread.start()

    def tearDown(self):
        self.node.destroy_node()

    def test_add_two_ints_exists(self):
        self.assertTrue(self.client_add_two_ints.wait_for_service(timeout_sec=5.0))

    def test_add_two_ints(self):
        req = AddTwoInts.Request(a=10, b=20)
        res = self.client_add_two_ints.call(req)
        self.assertEqual(res.sum, 30)

Testing

$ launch_test src/minimal_service/test/test_service_member_function.py 
[INFO] [launch]: All log files can be found below /home/ravi/.ros/log/2022-07-28-15-22-23-845507-dell-148344
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [service_member_function-1]: process started with pid [148347]
test_add_two_ints (test_service_member_function.TestMinimalService) ... ^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
[INFO] [service_member_function-1]: process has finished cleanly [pid 148347]
Processes under test stopped before tests completed

The test test_add_two_ints stays as it is and does not return. Later, I pressed Ctrl + C to terminate the process forcefully.

Weird Behavior

The setUp method contains an assertion statement. Surprisingly, both the test cases work if I uncomment the assertion. See below, please.

$ launch_test src/minimal_service/test/test_service_member_function.py 
[INFO] [launch]: All log files can be found below /home/ravi/.ros/log/2022-07-28-15-28-44-770728-dell-149020
[INFO] [launch]: Default logging verbosity is set to INFO
test_add_two_ints (test_service_member_function.TestMinimalService) ... [INFO] [service_member_function-1]: process started with pid [149023]
[service_member_function-1] [INFO] [1658989725.064503034] [minimal_service]: Incoming request
[service_member_function-1] a: 10 b: 20
ok
test_add_two_ints_exists (test_service_member_function.TestMinimalService) ... Exception in thread Thread-2:
Traceback (most recent call last):
  File "/usr/lib/python3.8/threading.py", line 932, in _bootstrap_inner
    self.run()
  File "/usr/lib/python3.8/threading.py", line 870, in run
ok

    self._target(*self._args, **self._kwargs)
----------------------------------------------------------------------
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/__init__.py", line 191, in spin
Ran 2 tests in 0.555s

OK
    executor.spin_once()
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 706, in spin_once
[INFO] [service_member_function-1]: sending signal 'SIGINT' to process[service_member_function-1]
    handler, entity, node = self.wait_for_ready_callbacks(timeout_sec=timeout_sec)
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 692, in wait_for_ready_callbacks
    return next(self._cb_iter)
ValueError: generator already executing
[INFO] [service_member_function-1]: process has finished cleanly [pid 149023]

----------------------------------------------------------------------
Ran 0 tests in 0.000s

OK

Additional Info

Below is the workspace structure:

.
├── build
├── install
├── log
└── src
    └── minimal_service
        ├── CHANGELOG.rst
        ├── examples_rclpy_minimal_service
        │   ├── __init__.py
        │   └── service_member_function.py
        ├── package.xml
        ├── README.md
        ├── resource
        │   └── examples_rclpy_minimal_service
        ├── setup.cfg
        ├── setup.py
        └── test
            ├── test_copyright.py
            ├── test_flake8.py
            ├── test_pep257.py
            └── test_service_member_function.py ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2022-08-18 10:34:41 -0600

ChuiV gravatar image

rclpy.spin doesn't exit until it receives the ctrl-c signal. I would recommend one of the following:

  • Don't use a spin thread. Manually spin the node with spin_once. At my company we've got a SpinUntil method that will spin the node until a lambda is true, or it times-out and we can handle that case.
  • If you must use a spin thread. In both cases, don't forget to do a join on your spin thread:
    • Use spin_until_future_complete instead of spin. This way you can set the future, and it'll stop the spinning.
    • Use a while still_testing: kind of loop with a spin_once (with the timeout!) so that you only spin as long as you need it to. Once your test is done, then you can still_testing = False in your tear down method and the spinning will eventually stop
edit flag offensive delete link more

Comments

1

Thank you very much.

If you must use a spin thread.

No, I don't. I want to write integration test cases for a node with publishers, subscribers, services, and actions.

  1. I understood the spin thread part, causing the test to stay alive. Hence it does not return.
  2. I could not understand why spin_until_future_complete is needed over res = self.client_add_two_ints.call(req)
  3. Is it possible to share SpinUntil with an example?
  4. Is it possible to elaborate more on while still_testing: with an example?

I made it work using spin_until_future_complete. Please verify my implementation here.

ravijoshi gravatar image ravijoshi  ( 2022-08-19 03:42:21 -0600 )edit

Please add your code to the question in the edit for future readers - links to Pastebin and similar sites expire quite fast

ljaniec gravatar image ljaniec  ( 2022-08-19 05:07:20 -0600 )edit
1

@ljaniec and @ChuiV: Thank you very much. I made changes to setUp, test_add_two_ints_exists, and test_add_two_ints as mentioned in the updated question above. Please see the "Update" section. The code may require additional re-factorization/improvements though.

ravijoshi gravatar image ravijoshi  ( 2022-08-20 03:36:26 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2022-07-28 01:41:09 -0600

Seen: 643 times

Last updated: Aug 20 '22