From 3a8f30e710620f472d1d37822bbca622e0caea99 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sat, 16 Nov 2019 16:43:53 -0800 Subject: [PATCH] Merge test_subscription* into test_subscription --- tracetools_test/CMakeLists.txt | 11 --- tracetools_test/src/test_ping.cpp | 5 +- tracetools_test/src/test_subscription.cpp | 59 --------------- tracetools_test/test/test_subscription.py | 72 ++++++++++++++++-- .../test/test_subscription_callback.py | 74 ------------------- 5 files changed, 70 insertions(+), 151 deletions(-) delete mode 100644 tracetools_test/src/test_subscription.cpp delete mode 100644 tracetools_test/test/test_subscription_callback.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index e744477..e6a7e44 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -47,15 +47,6 @@ if(BUILD_TESTING) tracetools ) target_link_libraries(test_publisher "${RDYNAMIC_FLAG}") - add_executable(test_subscription - src/test_subscription.cpp - ) - ament_target_dependencies(test_subscription - rclcpp - std_msgs - tracetools - ) - target_link_libraries(test_subscription "${RDYNAMIC_FLAG}") add_executable(test_intra src/test_intra.cpp ) @@ -127,7 +118,6 @@ if(BUILD_TESTING) test_service test_service_ping test_service_pong - test_subscription test_timer DESTINATION lib/${PROJECT_NAME} ) @@ -147,7 +137,6 @@ if(BUILD_TESTING) test/test_service.py test/test_service_callback.py test/test_subscription.py - test/test_subscription_callback.py test/test_timer.py ) diff --git a/tracetools_test/src/test_ping.cpp b/tracetools_test/src/test_ping.cpp index b419e72..ec62227 100644 --- a/tracetools_test/src/test_ping.cpp +++ b/tracetools_test/src/test_ping.cpp @@ -23,6 +23,7 @@ using namespace std::chrono_literals; #define NODE_NAME "test_ping" #define SUB_TOPIC_NAME "pong" #define PUB_TOPIC_NAME "ping" +#define QUEUE_DEPTH 10 class PingNode : public rclcpp::Node { @@ -32,11 +33,11 @@ public: { sub_ = this->create_subscription( SUB_TOPIC_NAME, - rclcpp::QoS(10), + rclcpp::QoS(QUEUE_DEPTH), std::bind(&PingNode::callback, this, std::placeholders::_1)); pub_ = this->create_publisher( PUB_TOPIC_NAME, - rclcpp::QoS(10)); + rclcpp::QoS(QUEUE_DEPTH)); timer_ = this->create_wall_timer( 500ms, std::bind(&PingNode::timer_callback, this)); diff --git a/tracetools_test/src/test_subscription.cpp b/tracetools_test/src/test_subscription.cpp deleted file mode 100644 index a13e37d..0000000 --- a/tracetools_test/src/test_subscription.cpp +++ /dev/null @@ -1,59 +0,0 @@ -// Copyright 2019 Robert Bosch GmbH -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" - -#define NODE_NAME "test_subscription" -#define TOPIC_NAME "the_topic" -#define QUEUE_DEPTH 10 - -class SubNode : public rclcpp::Node -{ -public: - explicit SubNode(rclcpp::NodeOptions options) - : Node(NODE_NAME, options) - { - sub_ = this->create_subscription( - TOPIC_NAME, - rclcpp::QoS(QUEUE_DEPTH), - std::bind(&SubNode::callback, this, std::placeholders::_1)); - } - -private: - void callback(const std_msgs::msg::String::SharedPtr msg) - { - // Nothing - (void)msg; - } - - rclcpp::Subscription::SharedPtr sub_; -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - - rclcpp::executors::SingleThreadedExecutor exec; - auto sub_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(sub_node); - - printf("spinning once\n"); - exec.spin_once(); - - rclcpp::shutdown(); - return 0; -} diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index e9f5ebd..9b5eac1 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -1,4 +1,5 @@ # Copyright 2019 Robert Bosch GmbH +# Copyright 2019 Apex.AI, Inc. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -22,14 +23,16 @@ class TestSubscription(TraceTestCase): def __init__(self, *args) -> None: super().__init__( *args, - session_name_prefix='session-test-subscription-creation', + session_name_prefix='session-test-subscription', events_ros=[ 'ros2:rcl_node_init', 'ros2:rcl_subscription_init', 'ros2:rclcpp_subscription_init', 'ros2:rclcpp_subscription_callback_added', + 'ros2:callback_start', + 'ros2:callback_end', ], - nodes=['test_subscription'], + nodes=['test_ping', 'test_pong'], ) def test_all(self): @@ -42,6 +45,8 @@ class TestSubscription(TraceTestCase): callback_added_events = self.get_events_with_name( 'ros2:rclcpp_subscription_callback_added', ) + start_events = self.get_events_with_name('ros2:callback_start') + end_events = self.get_events_with_name('ros2:callback_end') for event in rcl_sub_init_events: self.assertValidHandle( @@ -57,11 +62,22 @@ class TestSubscription(TraceTestCase): ) for event in callback_added_events: self.assertValidHandle(event, ['subscription', 'callback']) + 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}', + ) + for event in end_events: + self.assertValidHandle(event, 'callback') - # Check that the test topic name exists + # Check that the pong test topic name exists + # Note: using the ping node test_rcl_sub_init_events = self.get_events_with_field_value( 'topic_name', - '/the_topic', + '/pong', rcl_sub_init_events, ) self.assertNumEventsEqual(test_rcl_sub_init_events, 1, 'cannot find test topic name') @@ -78,7 +94,7 @@ class TestSubscription(TraceTestCase): # 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', + 'test_ping', node_init_events, ) self.assertNumEventsEqual( @@ -122,6 +138,52 @@ class TestSubscription(TraceTestCase): 'none or more than 1 rclcpp_sub_callback_added event for topic', ) + # Check that each start:end pair has a common callback handle + 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, + ) + + # Check that callback pointer matches between sub_callback_added and callback_start/end + # There is only one callback for /pong topic in ping node + callback_added_matching_event = callback_added_matching_events[0] + callback_pointer = self.get_field(callback_added_matching_event, 'callback') + callback_start_matching_events = self.get_events_with_field_value( + 'callback', + callback_pointer, + ping_events_start, + ) + self.assertNumEventsEqual( + callback_start_matching_events, + 1, + 'none or more than 1 callback_start event for topic callback', + ) + ping_events_end = self.get_events_with_name('ros2:callback_end', ping_events) + callback_end_matching_events = self.get_events_with_field_value( + 'callback', + callback_pointer, + ping_events_end, + ) + self.assertNumEventsEqual( + callback_end_matching_events, + 1, + 'none or more than 1 callback_end event for topic callback', + ) + if __name__ == '__main__': unittest.main() diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py deleted file mode 100644 index e1e2483..0000000 --- a/tracetools_test/test/test_subscription_callback.py +++ /dev/null @@ -1,74 +0,0 @@ -# Copyright 2019 Robert Bosch GmbH -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import unittest - -from tracetools_test.case import TraceTestCase - - -class TestSubscriptionCallback(TraceTestCase): - - def __init__(self, *args) -> None: - super().__init__( - *args, - session_name_prefix='session-test-subscription-callback', - events_ros=[ - 'ros2:callback_start', - 'ros2:callback_end', - ], - nodes=['test_ping', 'test_pong'], - ) - - def test_all(self): - # Check events as set - self.assertEventsSet(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 - 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__': - unittest.main()