Skip to content

Commit

Permalink
Use new test interface definitions (#332)
Browse files Browse the repository at this point in the history
* Use new test interface definitions

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Rename variables

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored May 1, 2019
1 parent d672075 commit d8948bb
Show file tree
Hide file tree
Showing 4 changed files with 33 additions and 33 deletions.
6 changes: 3 additions & 3 deletions rclpy/test/test_callback_group.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
import rclpy
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.callback_groups import ReentrantCallbackGroup
from test_msgs.msg import Primitives
from test_msgs.msg import BasicTypes


class TestCallbackGroup(unittest.TestCase):
Expand Down Expand Up @@ -71,10 +71,10 @@ def test_create_timer_with_group(self):
self.assertTrue(group.has_entity(tmr2))

def test_create_subscription_with_group(self):
sub1 = self.node.create_subscription(Primitives, 'chatter', lambda msg: print(msg))
sub1 = self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg))
group = ReentrantCallbackGroup()
sub2 = self.node.create_subscription(
Primitives, 'chatter', lambda msg: print(msg), callback_group=group)
BasicTypes, 'chatter', lambda msg: print(msg), callback_group=group)

self.assertFalse(group.has_entity(sub1))
self.assertTrue(group.has_entity(sub2))
Expand Down
20 changes: 10 additions & 10 deletions rclpy/test/test_destruction.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
import pytest
import rclpy
from rclpy.handle import InvalidHandle
from test_msgs.msg import Primitives
from test_msgs.srv import Primitives as PrimitivesSrv
from test_msgs.msg import BasicTypes
from test_msgs.srv import BasicTypes as BasicTypesSrv


def test_destroy_node():
Expand Down Expand Up @@ -71,16 +71,16 @@ def test_destroy_entities():
timer = node.create_timer(0.1, None)
timer # noqa
assert 1 == len(node.timers)
pub1 = node.create_publisher(Primitives, 'pub1_topic')
pub1 = node.create_publisher(BasicTypes, 'pub1_topic')
assert 2 == len(node.publishers)
pub2 = node.create_publisher(Primitives, 'pub2_topic')
pub2 = node.create_publisher(BasicTypes, 'pub2_topic')
pub2 # noqa
assert 3 == len(node.publishers)
sub1 = node.create_subscription(
Primitives, 'sub1_topic', lambda msg: ...)
BasicTypes, 'sub1_topic', lambda msg: ...)
assert 1 == len(node.subscriptions)
sub2 = node.create_subscription(
Primitives, 'sub2_topic', lambda msg: ...)
BasicTypes, 'sub2_topic', lambda msg: ...)
sub2 # noqa
assert 2 == len(node.subscriptions)

Expand All @@ -105,7 +105,7 @@ def test_destroy_subscription_asap():
try:
node = rclpy.create_node('test_destroy_subscription_asap', context=context)
try:
sub = node.create_subscription(Primitives, 'sub_topic', lambda msg: ...)
sub = node.create_subscription(BasicTypes, 'sub_topic', lambda msg: ...)

# handle valid
with sub.handle:
Expand Down Expand Up @@ -154,7 +154,7 @@ def test_destroy_publisher_asap():
try:
node = rclpy.create_node('test_destroy_publisher_asap', context=context)
try:
pub = node.create_publisher(Primitives, 'pub_topic')
pub = node.create_publisher(BasicTypes, 'pub_topic')

# handle valid
with pub.handle:
Expand Down Expand Up @@ -183,7 +183,7 @@ def test_destroy_client_asap():
try:
node = rclpy.create_node('test_destroy_client_asap', context=context)
try:
client = node.create_client(PrimitivesSrv, 'cli_service')
client = node.create_client(BasicTypesSrv, 'cli_service')

# handle valid
with client.handle:
Expand Down Expand Up @@ -212,7 +212,7 @@ def test_destroy_service_asap():
try:
node = rclpy.create_node('test_destroy_service_asap', context=context)
try:
service = node.create_service(PrimitivesSrv, 'srv_service', lambda req, res: ...)
service = node.create_service(BasicTypesSrv, 'srv_service', lambda req, res: ...)

# handle valid
with service.handle:
Expand Down
8 changes: 4 additions & 4 deletions rclpy/test/test_messages.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

import rclpy

from test_msgs.msg import Primitives
from test_msgs.msg import BasicTypes, Strings


class TestMessages(unittest.TestCase):
Expand All @@ -40,13 +40,13 @@ def tearDownClass(cls):
rclpy.shutdown(context=cls.context)

def test_invalid_string_raises(self):
msg = Primitives()
msg = Strings()
msg.string_value = 'ñu'
pub = self.node.create_publisher(Primitives, 'chatter')
pub = self.node.create_publisher(Strings, 'chatter')
with self.assertRaises(UnicodeEncodeError):
pub.publish(msg)

def test_different_type_raises(self):
pub = self.node.create_publisher(Primitives, 'chatter')
pub = self.node.create_publisher(BasicTypes, 'chatter')
with self.assertRaises(TypeError):
pub.publish('different message type')
32 changes: 16 additions & 16 deletions rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
from rclpy.exceptions import InvalidTopicNameException
from rclpy.executors import SingleThreadedExecutor
from rclpy.parameter import Parameter
from test_msgs.msg import Primitives
from test_msgs.msg import BasicTypes

TEST_NODE = 'my_node'
TEST_NAMESPACE = '/my_ns'
Expand Down Expand Up @@ -51,22 +51,22 @@ def test_accessors(self):
self.assertEqual(self.node.get_clock().clock_type, ClockType.ROS_TIME)

def test_create_publisher(self):
self.node.create_publisher(Primitives, 'chatter')
self.node.create_publisher(BasicTypes, 'chatter')
with self.assertRaisesRegex(InvalidTopicNameException, 'must not contain characters'):
self.node.create_publisher(Primitives, 'chatter?')
self.node.create_publisher(BasicTypes, 'chatter?')
with self.assertRaisesRegex(InvalidTopicNameException, 'must not start with a number'):
self.node.create_publisher(Primitives, '/chatter/42_is_the_answer')
self.node.create_publisher(BasicTypes, '/chatter/42_is_the_answer')
with self.assertRaisesRegex(ValueError, 'unknown substitution'):
self.node.create_publisher(Primitives, 'chatter/{bad_sub}')
self.node.create_publisher(BasicTypes, 'chatter/{bad_sub}')

def test_create_subscription(self):
self.node.create_subscription(Primitives, 'chatter', lambda msg: print(msg))
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg))
with self.assertRaisesRegex(InvalidTopicNameException, 'must not contain characters'):
self.node.create_subscription(Primitives, 'chatter?', lambda msg: print(msg))
self.node.create_subscription(BasicTypes, 'chatter?', lambda msg: print(msg))
with self.assertRaisesRegex(InvalidTopicNameException, 'must not start with a number'):
self.node.create_subscription(Primitives, '/chatter/42ish', lambda msg: print(msg))
self.node.create_subscription(BasicTypes, '/chatter/42ish', lambda msg: print(msg))
with self.assertRaisesRegex(ValueError, 'unknown substitution'):
self.node.create_subscription(Primitives, 'foo/{bad_sub}', lambda msg: print(msg))
self.node.create_subscription(BasicTypes, 'foo/{bad_sub}', lambda msg: print(msg))

def raw_subscription_callback(self, msg):
print('Raw subscription callback: %s length %d' % (msg, len(msg)))
Expand All @@ -75,18 +75,18 @@ def raw_subscription_callback(self, msg):
def test_create_raw_subscription(self):
executor = SingleThreadedExecutor(context=self.context)
executor.add_node(self.node)
primitives_pub = self.node.create_publisher(Primitives, 'raw_subscription_test')
basic_types_pub = self.node.create_publisher(BasicTypes, 'raw_subscription_test')
self.raw_subscription_msg = None # None=No result yet
self.node.create_subscription(
Primitives,
BasicTypes,
'raw_subscription_test',
self.raw_subscription_callback,
raw=True
)
primitives_msg = Primitives()
basic_types_msg = BasicTypes()
cycle_count = 0
while cycle_count < 5 and self.raw_subscription_msg is None:
primitives_pub.publish(primitives_msg)
basic_types_pub.publish(basic_types_msg)
cycle_count += 1
executor.spin_once(timeout_sec=1)
self.assertIsNotNone(self.raw_subscription_msg, 'raw subscribe timed out')
Expand Down Expand Up @@ -139,15 +139,15 @@ def test_count_publishers_subscribers(self):
self.assertEqual(0, self.node.count_publishers(fq_topic_name))
self.assertEqual(0, self.node.count_subscribers(fq_topic_name))

self.node.create_publisher(Primitives, short_topic_name)
self.node.create_publisher(BasicTypes, short_topic_name)
self.assertEqual(1, self.node.count_publishers(short_topic_name))
self.assertEqual(1, self.node.count_publishers(fq_topic_name))

self.node.create_subscription(Primitives, short_topic_name, lambda msg: print(msg))
self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg))
self.assertEqual(1, self.node.count_subscribers(short_topic_name))
self.assertEqual(1, self.node.count_subscribers(fq_topic_name))

self.node.create_subscription(Primitives, short_topic_name, lambda msg: print(msg))
self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg))
self.assertEqual(2, self.node.count_subscribers(short_topic_name))
self.assertEqual(2, self.node.count_subscribers(fq_topic_name))

Expand Down

0 comments on commit d8948bb

Please sign in to comment.