Skip to content

Commit

Permalink
Merge pull request #649 from ros2/clalancette/dont-except-while-sleep
Browse files Browse the repository at this point in the history
Don't throw an exception if timer canceled while sleeping.
  • Loading branch information
tfoote authored Dec 15, 2020
2 parents 71ba65d + e2ba3ba commit 22816b4
Showing 1 changed file with 11 additions and 1 deletion.
12 changes: 11 additions & 1 deletion rclpy/test/test_rate.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

import pytest
import rclpy
from rclpy.exceptions import ROSInterruptException
from rclpy.executors import SingleThreadedExecutor

# Hz
Expand Down Expand Up @@ -111,6 +112,15 @@ def test_destroy_wakes_rate(self):
self._thread.join()


def sleep_check_exception(rate):
try:
rate.sleep()
except ROSInterruptException:
# rate.sleep() can raise ROSInterruptException if the context is
# shutdown while it is sleeping. Just ignore it here.
pass


def test_shutdown_wakes_rate():
context = rclpy.context.Context()
rclpy.init(context=context)
Expand All @@ -120,7 +130,7 @@ def test_shutdown_wakes_rate():

rate = node.create_rate(0.0000001)

_thread = threading.Thread(target=rate.sleep, daemon=True)
_thread = threading.Thread(target=sleep_check_exception, args=(rate,), daemon=True)
_thread.start()
executor.shutdown()
node.destroy_node()
Expand Down

0 comments on commit 22816b4

Please sign in to comment.