From b7fc66a8819ef0f6935ad17260832b4df8e9a13e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 21 Jun 2019 09:58:33 +0200 Subject: [PATCH] Check queue_depth value in pub and sub tests --- tracetools_test/src/test_publisher.cpp | 3 ++- tracetools_test/src/test_subscription.cpp | 3 ++- tracetools_test/test/test_publisher.py | 18 ++++++++++++++++-- tracetools_test/test/test_subscription.py | 7 +++++++ 4 files changed, 27 insertions(+), 4 deletions(-) diff --git a/tracetools_test/src/test_publisher.cpp b/tracetools_test/src/test_publisher.cpp index c0d57a7..f1d2f26 100644 --- a/tracetools_test/src/test_publisher.cpp +++ b/tracetools_test/src/test_publisher.cpp @@ -19,6 +19,7 @@ #define NODE_NAME "test_publisher" #define TOPIC_NAME "the_topic" +#define QUEUE_DEPTH 10 class PubNode : public rclcpp::Node { @@ -28,7 +29,7 @@ public: { pub_ = this->create_publisher( TOPIC_NAME, - rclcpp::QoS(10)); + rclcpp::QoS(QUEUE_DEPTH)); } private: diff --git a/tracetools_test/src/test_subscription.cpp b/tracetools_test/src/test_subscription.cpp index 3f3ce82..a13e37d 100644 --- a/tracetools_test/src/test_subscription.cpp +++ b/tracetools_test/src/test_subscription.cpp @@ -19,6 +19,7 @@ #define NODE_NAME "test_subscription" #define TOPIC_NAME "the_topic" +#define QUEUE_DEPTH 10 class SubNode : public rclcpp::Node { @@ -28,7 +29,7 @@ public: { sub_ = this->create_subscription( TOPIC_NAME, - rclcpp::QoS(10), + rclcpp::QoS(QUEUE_DEPTH), std::bind(&SubNode::callback, this, std::placeholders::_1)); } diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index 1abe87b..31c4cb0 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -45,8 +45,22 @@ class TestPublisher(TraceTestCase): # 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') + test_pub_init_topic_events = self.get_events_with_field_value( + 'topic_name', + '/the_topic', + test_pub_init_events) + self.assertEqual( + len(test_pub_init_topic_events), + 1, + 'none or more than 1 pub_init even for test topic') + + # Check queue_depth value + test_pub_init_topic_event = test_pub_init_topic_events[0] + test_queue_depth = self.get_field(test_pub_init_topic_event, 'queue_depth') + self.assertEqual( + test_queue_depth, + 10, + 'pub_init event does not have expected queue depth value') # Check that the node handle matches with the node_init event node_init_events = self.get_events_with_name('ros2:rcl_node_init') diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 85d22a0..f724591 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -57,6 +57,13 @@ class TestSubscription(TraceTestCase): self.assertEqual(len(test_sub_init_events), 1, 'cannot find test topic name') test_sub_init_event = test_sub_init_events[0] + # Check queue_depth value + test_queue_depth = self.get_field(test_sub_init_event, 'queue_depth') + self.assertEqual( + test_queue_depth, + 10, + 'sub_init event does not have expected queue depth value') + # 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(