Add more tests and more test utils
This commit is contained in:
parent
20cf197b87
commit
eb8a7e2c26
10 changed files with 389 additions and 23 deletions
|
@ -34,7 +34,7 @@ class TestNode(TraceTestCase):
|
|||
)
|
||||
|
||||
def test_all(self):
|
||||
# Check events order as set
|
||||
# Check events order as set (e.g. init before node_init)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
|
@ -47,8 +47,7 @@ class TestNode(TraceTestCase):
|
|||
|
||||
rcl_node_init_events = self.get_events_with_name('ros2:rcl_node_init')
|
||||
for event in rcl_node_init_events:
|
||||
self.assertValidHandle(event, 'node_handle')
|
||||
self.assertValidHandle(event, 'rmw_handle')
|
||||
self.assertValidHandle(event, ['node_handle', 'rmw_handle'])
|
||||
self.assertStringFieldNotEmpty(event, 'node_name')
|
||||
self.assertStringFieldNotEmpty(event, 'namespace')
|
||||
|
||||
|
|
|
@ -24,13 +24,42 @@ class TestPublisher(TraceTestCase):
|
|||
*args,
|
||||
session_name_prefix='session-test-publisher-creation',
|
||||
events_ros=[
|
||||
'ros2:rcl_node_init',
|
||||
'ros2:rcl_publisher_init',
|
||||
],
|
||||
nodes=['test_publisher']
|
||||
)
|
||||
|
||||
def test_creation(self):
|
||||
pass
|
||||
def test_all(self):
|
||||
# Check events order as set (e.g. node_init before pub_init)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
pub_init_events = self.get_events_with_name('ros2:rcl_publisher_init')
|
||||
for event in pub_init_events:
|
||||
self.assertValidHandle(
|
||||
event,
|
||||
['publisher_handle', 'node_handle', 'rmw_publisher_handle'])
|
||||
self.assertValidQueueDepth(event, 'queue_depth')
|
||||
self.assertStringFieldNotEmpty(event, 'topic_name')
|
||||
|
||||
# Check that the test topic name exists
|
||||
test_pub_init_events = self.get_events_with_procname('test_publisher', pub_init_events)
|
||||
event_topic_names = [self.get_field(e, 'topic_name') for e in test_pub_init_events]
|
||||
self.assertTrue('/the_topic' in event_topic_names, 'cannot find test topic name')
|
||||
|
||||
# Check that the node handle matches with the node_init event
|
||||
node_init_events = self.get_events_with_name('ros2:rcl_node_init')
|
||||
test_pub_node_init_events = self.get_events_with_procname(
|
||||
'test_publisher',
|
||||
node_init_events)
|
||||
self.assertEqual(len(test_pub_node_init_events), 1, 'none or more than 1 node_init event')
|
||||
test_pub_node_init_event = test_pub_node_init_events[0]
|
||||
self.assertMatchingField(
|
||||
test_pub_node_init_event,
|
||||
'node_handle',
|
||||
None,
|
||||
test_pub_init_events)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -24,14 +24,58 @@ class TestService(TraceTestCase):
|
|||
*args,
|
||||
session_name_prefix='session-test-service-creation',
|
||||
events_ros=[
|
||||
'ros2:rcl_node_init',
|
||||
'ros2:rcl_service_init',
|
||||
'ros2:rclcpp_service_callback_added',
|
||||
],
|
||||
nodes=['test_service']
|
||||
)
|
||||
|
||||
def test_creation(self):
|
||||
pass
|
||||
def test_all(self):
|
||||
# Check events order as set (e.g. service_init before callback_added)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
srv_init_events = self.get_events_with_name('ros2:rcl_service_init')
|
||||
for event in srv_init_events:
|
||||
self.assertValidHandle(event, ['service_handle', 'node_handle', 'rmw_service_handle'])
|
||||
self.assertStringFieldNotEmpty(event, 'service_name')
|
||||
|
||||
callback_added_events = self.get_events_with_name('ros2:rclcpp_service_callback_added')
|
||||
for event in callback_added_events:
|
||||
self.assertValidHandle(event, ['service_handle', 'callback'])
|
||||
|
||||
# Check that the test service name exists
|
||||
test_srv_init_events = self.get_events_with_procname('test_service', srv_init_events)
|
||||
event_service_names = self.get_events_with_field_value(
|
||||
'service_name',
|
||||
'/the_service',
|
||||
test_srv_init_events)
|
||||
self.assertGreaterEqual(
|
||||
len(event_service_names),
|
||||
1,
|
||||
'cannot find test service name')
|
||||
|
||||
# Check that the node handle matches the node_init event
|
||||
node_init_events = self.get_events_with_name('ros2:rcl_node_init')
|
||||
test_srv_node_init_events = self.get_events_with_procname(
|
||||
'test_service',
|
||||
node_init_events)
|
||||
self.assertEqual(len(test_srv_node_init_events), 1, 'none or more than 1 node_init event')
|
||||
test_srv_node_init_event = test_srv_node_init_events[0]
|
||||
self.assertMatchingField(
|
||||
test_srv_node_init_event,
|
||||
'node_handle',
|
||||
'ros2:rcl_service_init',
|
||||
test_srv_init_events)
|
||||
|
||||
# Check that the service handles match
|
||||
test_event_srv_init = event_service_names[0]
|
||||
self.assertMatchingField(
|
||||
test_event_srv_init,
|
||||
'service_handle',
|
||||
None,
|
||||
callback_added_events)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -30,8 +30,32 @@ class TestServiceCallback(TraceTestCase):
|
|||
nodes=['test_service_ping', 'test_service_pong']
|
||||
)
|
||||
|
||||
def test_callback(self):
|
||||
pass
|
||||
def test_all(self):
|
||||
# Check events order as set (e.g. start before end)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
start_events = self.get_events_with_name('ros2:callback_start')
|
||||
for event in start_events:
|
||||
self.assertValidHandle(event, 'callback')
|
||||
is_intra_process_value = self.get_field(event, 'is_intra_process')
|
||||
self.assertIsInstance(is_intra_process_value, int, 'is_intra_process not int')
|
||||
# Should not be 1 for services (yet)
|
||||
self.assertEqual(
|
||||
is_intra_process_value,
|
||||
0,
|
||||
f'invalid value for is_intra_process: {is_intra_process_value}')
|
||||
|
||||
end_events = self.get_events_with_name('ros2:callback_end')
|
||||
for event in end_events:
|
||||
self.assertValidHandle(event, 'callback')
|
||||
|
||||
# Check that there is at least a start/end pair for each node
|
||||
for node in self._nodes:
|
||||
test_start_events = self.get_events_with_procname(node, start_events)
|
||||
test_end_events = self.get_events_with_procname(node, end_events)
|
||||
self.assertGreater(len(test_start_events), 0, f'no start_callback events for node: {node}')
|
||||
self.assertGreater(len(test_end_events), 0, f'no end_callback events for node: {node}')
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -24,14 +24,60 @@ class TestSubscription(TraceTestCase):
|
|||
*args,
|
||||
session_name_prefix='session-test-subscription-creation',
|
||||
events_ros=[
|
||||
'ros2:rcl_node_init',
|
||||
'ros2:rcl_subscription_init',
|
||||
'ros2:rclcpp_subscription_callback_added',
|
||||
],
|
||||
nodes=['test_subscription']
|
||||
)
|
||||
|
||||
def test_creation(self):
|
||||
pass
|
||||
def test_all(self):
|
||||
# Check events order as set (e.g. sub_init before callback_added)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init')
|
||||
for event in sub_init_events:
|
||||
self.assertValidHandle(
|
||||
event,
|
||||
['subscription_handle', 'node_handle', 'rmw_subscription_handle'])
|
||||
self.assertValidQueueDepth(event, 'queue_depth')
|
||||
self.assertStringFieldNotEmpty(event, 'topic_name')
|
||||
|
||||
callback_added_events = self.get_events_with_name('ros2:rclcpp_subscription_callback_added')
|
||||
for event in callback_added_events:
|
||||
self.assertValidHandle(event, ['subscription_handle', 'callback'])
|
||||
|
||||
# Check that the test topic name exists
|
||||
test_sub_init_events = self.get_events_with_field_value(
|
||||
'topic_name',
|
||||
'/the_topic',
|
||||
sub_init_events)
|
||||
self.assertEqual(len(test_sub_init_events), 1, 'cannot find test topic name')
|
||||
test_sub_init_event = test_sub_init_events[0]
|
||||
|
||||
# Check that the node handle matches the node_init event
|
||||
node_init_events = self.get_events_with_name('ros2:rcl_node_init')
|
||||
test_sub_node_init_events = self.get_events_with_procname(
|
||||
'test_subscription',
|
||||
node_init_events)
|
||||
self.assertEqual(
|
||||
len(test_sub_node_init_events),
|
||||
1,
|
||||
'none or more than 1 node_init event')
|
||||
test_sub_node_init_event = test_sub_node_init_events[0]
|
||||
self.assertMatchingField(
|
||||
test_sub_node_init_event,
|
||||
'node_handle',
|
||||
'ros2:rcl_subscription_init',
|
||||
sub_init_events)
|
||||
|
||||
# Check that subscription handle matches with callback_added event
|
||||
self.assertMatchingField(
|
||||
test_sub_init_event,
|
||||
'subscription_handle',
|
||||
None,
|
||||
callback_added_events)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -30,8 +30,42 @@ class TestSubscriptionCallback(TraceTestCase):
|
|||
nodes=['test_ping', 'test_pong']
|
||||
)
|
||||
|
||||
def test_callback(self):
|
||||
pass
|
||||
def test_all(self):
|
||||
# Check events order as set (e.g. start before end)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
start_events = self.get_events_with_name('ros2:callback_start')
|
||||
for event in start_events:
|
||||
self.assertValidHandle(event, 'callback')
|
||||
is_intra_process_value = self.get_field(event, 'is_intra_process')
|
||||
self.assertIsInstance(is_intra_process_value, int, 'is_intra_process not int')
|
||||
self.assertTrue(
|
||||
is_intra_process_value in [0, 1],
|
||||
f'invalid value for is_intra_process: {is_intra_process_value}')
|
||||
|
||||
end_events = self.get_events_with_name('ros2:callback_end')
|
||||
for event in end_events:
|
||||
self.assertValidHandle(event, 'callback')
|
||||
|
||||
# Check that a start:end pair has a common callback handle
|
||||
# Note: might be unstable if tracing is disabled too early
|
||||
ping_events = self.get_events_with_procname('test_ping')
|
||||
pong_events = self.get_events_with_procname('test_pong')
|
||||
ping_events_start = self.get_events_with_name('ros2:callback_start', ping_events)
|
||||
pong_events_start = self.get_events_with_name('ros2:callback_start', pong_events)
|
||||
for ping_start in ping_events_start:
|
||||
self.assertMatchingField(
|
||||
ping_start,
|
||||
'callback',
|
||||
'ros2:callback_end',
|
||||
ping_events)
|
||||
for pong_start in pong_events_start:
|
||||
self.assertMatchingField(
|
||||
pong_start,
|
||||
'callback',
|
||||
'ros2:callback_end',
|
||||
pong_events)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -33,7 +33,58 @@ class TestTimer(TraceTestCase):
|
|||
)
|
||||
|
||||
def test_all(self):
|
||||
pass
|
||||
# Check events order as set (e.g. init, callback added, start, end)
|
||||
self.assertEventsOrderSet(self._events_ros)
|
||||
|
||||
# Check fields
|
||||
init_events = self.get_events_with_name('ros2:rcl_timer_init')
|
||||
for event in init_events:
|
||||
self.assertValidHandle(event, 'timer_handle')
|
||||
period_value = self.get_field(event, 'period')
|
||||
self.assertIsInstance(period_value, int)
|
||||
self.assertGreaterEqual(period_value, 0, f'invalid period value: {period_value}')
|
||||
|
||||
callback_added_events = self.get_events_with_name('ros2:rclcpp_timer_callback_added')
|
||||
for event in callback_added_events:
|
||||
self.assertValidHandle(event, ['timer_handle', 'callback'])
|
||||
|
||||
start_events = self.get_events_with_name('ros2:callback_start')
|
||||
for event in start_events:
|
||||
self.assertValidHandle(event, 'callback')
|
||||
is_intra_process_value = self.get_field(event, 'is_intra_process')
|
||||
self.assertIsInstance(is_intra_process_value, int, 'is_intra_process not int')
|
||||
# Should not be 1 for timer
|
||||
self.assertEqual(
|
||||
is_intra_process_value,
|
||||
0,
|
||||
f'invalid value for is_intra_process: {is_intra_process_value}')
|
||||
|
||||
end_events = self.get_events_with_name('ros2:callback_end')
|
||||
for event in end_events:
|
||||
self.assertValidHandle(event, 'callback')
|
||||
|
||||
# Find and check given timer period
|
||||
test_timer_init_event = self.get_events_with_procname('test_timer', init_events)
|
||||
self.assertEqual(len(test_timer_init_event), 1)
|
||||
test_init_event = test_timer_init_event[0]
|
||||
test_period = self.get_field(test_init_event, 'period')
|
||||
self.assertIsInstance(test_period, int)
|
||||
self.assertEqual(test_period, 1000000, f'invalid period: {test_period}')
|
||||
|
||||
# Check that the timer_init:callback_added pair exists and has a common timer handle
|
||||
self.assertMatchingField(
|
||||
test_init_event,
|
||||
'timer_handle',
|
||||
'ros2:rclcpp_timer_callback_added',
|
||||
callback_added_events)
|
||||
|
||||
# Check that a callback start:end pair has a common callback handle
|
||||
for start_event in start_events:
|
||||
self.assertMatchingField(
|
||||
start_event,
|
||||
'callback',
|
||||
None,
|
||||
end_events)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue