Skip to content

Commit

Permalink
Shutdown context after test (ros2#267)
Browse files Browse the repository at this point in the history
Fixes ros2#266

Otherwise, running the test repeatedly causes runtime errors.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Sep 16, 2021
1 parent 798995e commit ea07def
Showing 1 changed file with 13 additions and 6 deletions.
19 changes: 13 additions & 6 deletions test_launch_ros/test/test_launch_ros/actions/test_ros_timer.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import RosTimer
from launch_ros.actions import SetUseSimTime
import pytest
import rclpy
from rclpy.clock import Clock, ClockType
from rosgraph_msgs.msg import Clock as ClockMsg
Expand Down Expand Up @@ -148,12 +149,18 @@ def test_shutdown_preempts_timers():
assert shutdown_reasons[0].reason == 'fast shutdown'


def test_timer_uses_sim_time():
"""Test that timer uses time from /clock topic."""
# Create clock publisher node
@pytest.fixture
def rclpy_node():
rclpy.init()
node = rclpy.create_node('test_ros_timer_action_node')
publisher = node.create_publisher(ClockMsg, '/clock', 10)
yield node
rclpy.shutdown()


def test_timer_uses_sim_time(rclpy_node):
"""Test that timer uses time from /clock topic."""
# Create clock publisher node
publisher = rclpy_node.create_publisher(ClockMsg, '/clock', 10)

# Increment sim time by 100 every time callback is called
def timer_callback(publisher, time_msg):
Expand All @@ -163,9 +170,9 @@ def timer_callback(publisher, time_msg):
# For every second of system time, publish new sim time value
callback_clock = Clock(clock_type=ClockType.SYSTEM_TIME)
time_msg = Time(sec=0, nanosec=0)
node.create_timer(1, partial(timer_callback, publisher, time_msg), clock=callback_clock)
rclpy_node.create_timer(1, partial(timer_callback, publisher, time_msg), clock=callback_clock)

thread = threading.Thread(target=rclpy.spin, args=(node, ), daemon=True)
thread = threading.Thread(target=rclpy.spin, args=(rclpy_node, ), daemon=True)
thread.start()

ld = launch.LaunchDescription([
Expand Down

0 comments on commit ea07def

Please sign in to comment.