Skip to content

Commit

Permalink
More tests using S_TO_NS
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Oct 17, 2017
1 parent f0b36e8 commit 14f3bc7
Showing 1 changed file with 5 additions and 4 deletions.
9 changes: 5 additions & 4 deletions rclpy/test/test_wait_set.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

from rcl_interfaces.srv import GetParameters
import rclpy
from rclpy.constants import S_TO_NS
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.wait_set import WaitSet
from std_msgs.msg import String
Expand Down Expand Up @@ -52,15 +53,15 @@ def test_guard_condition_ready(self):

def test_timer_ready(self):
ws = WaitSet()
timer_handle, timer_pointer = _rclpy.rclpy_create_timer(100000000)
timer_handle, timer_pointer = _rclpy.rclpy_create_timer(int(0.1 * S_TO_NS))
try:
ws.add_timer(timer_handle, timer_pointer)
self.assertFalse(ws.is_ready(timer_pointer))

ws.wait(1)
self.assertFalse(ws.is_ready(timer_pointer))

ws.wait(100000000)
ws.wait(int(0.1 * S_TO_NS))
self.assertTrue(ws.is_ready(timer_pointer))
finally:
_rclpy.rclpy_destroy_entity('timer', timer_handle)
Expand All @@ -81,7 +82,7 @@ def test_subscriber_ready(self):
msg.data = 'Hello World'
pub.publish(msg)

ws.wait(5000000000)
ws.wait(5 * S_TO_NS)
self.assertTrue(ws.is_ready(sub.subscription_pointer))
finally:
self.node.destroy_publisher(pub)
Expand All @@ -106,7 +107,7 @@ def test_server_ready(self):
cli.wait_for_service()
cli.call(GetParameters.Request())

ws.wait(5000000000)
ws.wait(5 * S_TO_NS)
# TODO(sloretz) test client after it's wait_for_future() API is sorted out
self.assertTrue(ws.is_ready(srv.service_pointer))
finally:
Expand Down

0 comments on commit 14f3bc7

Please sign in to comment.