Update test_subscription after new intra-process communications

This commit is contained in:
Christophe Bedard 2019-11-16 15:56:50 -08:00
parent 841bc50f65
commit 7c0e5712b1

View file

@ -26,9 +26,10 @@ class TestSubscription(TraceTestCase):
events_ros=[ events_ros=[
'ros2:rcl_node_init', 'ros2:rcl_node_init',
'ros2:rcl_subscription_init', 'ros2:rcl_subscription_init',
'ros2:rclcpp_subscription_init',
'ros2:rclcpp_subscription_callback_added', 'ros2:rclcpp_subscription_callback_added',
], ],
nodes=['test_subscription'] nodes=['test_subscription'],
) )
def test_all(self): def test_all(self):
@ -36,56 +37,90 @@ class TestSubscription(TraceTestCase):
self.assertEventsSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init') rcl_sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init')
for event in sub_init_events: rclcpp_sub_init_events = self.get_events_with_name('ros2:rclcpp_subscription_init')
callback_added_events = self.get_events_with_name(
'ros2:rclcpp_subscription_callback_added',
)
for event in rcl_sub_init_events:
self.assertValidHandle( self.assertValidHandle(
event, event,
['subscription_handle', 'node_handle', 'rmw_subscription_handle']) ['subscription_handle', 'node_handle', 'rmw_subscription_handle'],
)
self.assertValidQueueDepth(event, 'queue_depth') self.assertValidQueueDepth(event, 'queue_depth')
self.assertStringFieldNotEmpty(event, 'topic_name') self.assertStringFieldNotEmpty(event, 'topic_name')
for event in rclcpp_sub_init_events:
callback_added_events = self.get_events_with_name( self.assertValidHandle(
'ros2:rclcpp_subscription_callback_added') event,
['subscription_handle', 'subscription'],
)
for event in callback_added_events: for event in callback_added_events:
self.assertValidHandle(event, ['subscription_handle', 'callback']) self.assertValidHandle(event, ['subscription', 'callback'])
# Check that the test topic name exists # Check that the test topic name exists
test_sub_init_events = self.get_events_with_field_value( test_rcl_sub_init_events = self.get_events_with_field_value(
'topic_name', 'topic_name',
'/the_topic', '/the_topic',
sub_init_events) rcl_sub_init_events,
self.assertNumEventsEqual(test_sub_init_events, 1, 'cannot find test topic name') )
test_sub_init_event = test_sub_init_events[0] self.assertNumEventsEqual(test_rcl_sub_init_events, 1, 'cannot find test topic name')
test_rcl_sub_init_event = test_rcl_sub_init_events[0]
# Check queue_depth value # Check queue_depth value
self.assertFieldEquals( self.assertFieldEquals(
test_sub_init_event, test_rcl_sub_init_event,
'queue_depth', 'queue_depth',
10, 10,
'sub_init event does not have expected queue depth value') 'sub_init event does not have expected queue depth value',
)
# Check that the node handle matches the node_init event # Check that the node handle matches the node_init event
node_init_events = self.get_events_with_name('ros2:rcl_node_init') node_init_events = self.get_events_with_name('ros2:rcl_node_init')
test_sub_node_init_events = self.get_events_with_procname( test_sub_node_init_events = self.get_events_with_procname(
'test_subscription', 'test_subscription',
node_init_events) node_init_events,
)
self.assertNumEventsEqual( self.assertNumEventsEqual(
test_sub_node_init_events, test_sub_node_init_events,
1, 1,
'none or more than 1 node_init event') 'none or more than 1 node_init event',
)
test_sub_node_init_event = test_sub_node_init_events[0] test_sub_node_init_event = test_sub_node_init_events[0]
self.assertMatchingField( self.assertMatchingField(
test_sub_node_init_event, test_sub_node_init_event,
'node_handle', 'node_handle',
'ros2:rcl_subscription_init', 'ros2:rcl_subscription_init',
sub_init_events) rcl_sub_init_events,
)
# Check that subscription handle matches with callback_added event # Check that subscription handle matches between rcl_sub_init and rclcpp_sub_init
self.assertMatchingField( subscription_handle = self.get_field(test_rcl_sub_init_event, 'subscription_handle')
test_sub_init_event, rclcpp_sub_init_matching_events = self.get_events_with_field_value(
'subscription_handle', 'subscription_handle',
None, subscription_handle,
callback_added_events) rclcpp_sub_init_events,
)
# Should only have 1 rclcpp_sub_init event, since intra-process is not enabled
self.assertNumEventsEqual(
rclcpp_sub_init_matching_events,
1,
'none or more than 1 rclcpp_sub_init event for topic',
)
# Check that subscription pointer matches between rclcpp_sub_init and sub_callback_added
rclcpp_sub_init_matching_event = rclcpp_sub_init_matching_events[0]
subscription_pointer = self.get_field(rclcpp_sub_init_matching_event, 'subscription')
callback_added_matching_events = self.get_events_with_field_value(
'subscription',
subscription_pointer,
callback_added_events,
)
self.assertNumEventsEqual(
callback_added_matching_events,
1,
'none or more than 1 rclcpp_sub_callback_added event for topic',
)
if __name__ == '__main__': if __name__ == '__main__':