Check queue_depth value in pub and sub tests

This commit is contained in:
Christophe Bedard 2019-06-21 09:58:33 +02:00
parent 8917400c74
commit b7fc66a881
4 changed files with 27 additions and 4 deletions

View file

@ -19,6 +19,7 @@
#define NODE_NAME "test_publisher" #define NODE_NAME "test_publisher"
#define TOPIC_NAME "the_topic" #define TOPIC_NAME "the_topic"
#define QUEUE_DEPTH 10
class PubNode : public rclcpp::Node class PubNode : public rclcpp::Node
{ {
@ -28,7 +29,7 @@ public:
{ {
pub_ = this->create_publisher<std_msgs::msg::String>( pub_ = this->create_publisher<std_msgs::msg::String>(
TOPIC_NAME, TOPIC_NAME,
rclcpp::QoS(10)); rclcpp::QoS(QUEUE_DEPTH));
} }
private: private:

View file

@ -19,6 +19,7 @@
#define NODE_NAME "test_subscription" #define NODE_NAME "test_subscription"
#define TOPIC_NAME "the_topic" #define TOPIC_NAME "the_topic"
#define QUEUE_DEPTH 10
class SubNode : public rclcpp::Node class SubNode : public rclcpp::Node
{ {
@ -28,7 +29,7 @@ public:
{ {
sub_ = this->create_subscription<std_msgs::msg::String>( sub_ = this->create_subscription<std_msgs::msg::String>(
TOPIC_NAME, TOPIC_NAME,
rclcpp::QoS(10), rclcpp::QoS(QUEUE_DEPTH),
std::bind(&SubNode::callback, this, std::placeholders::_1)); std::bind(&SubNode::callback, this, std::placeholders::_1));
} }

View file

@ -45,8 +45,22 @@ class TestPublisher(TraceTestCase):
# Check that the test topic name exists # Check that the test topic name exists
test_pub_init_events = self.get_events_with_procname('test_publisher', pub_init_events) 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] test_pub_init_topic_events = self.get_events_with_field_value(
self.assertTrue('/the_topic' in event_topic_names, 'cannot find test topic name') '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 # Check that the node handle matches with 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')

View file

@ -57,6 +57,13 @@ class TestSubscription(TraceTestCase):
self.assertEqual(len(test_sub_init_events), 1, 'cannot find test topic name') self.assertEqual(len(test_sub_init_events), 1, 'cannot find test topic name')
test_sub_init_event = test_sub_init_events[0] 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 # 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(