From 97631f56080935e9485dd342f25c53fc0d0ef957 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Mon, 26 Aug 2024 10:54:30 -0700 Subject: [PATCH] Make test_tracetools ping pubs/subs transient_local (#125) (#135) This will make sure that the initial `/ping` message is received no matter the launch order of the `*ping` and `*pong` executables. Also, given this guarantee, cancel the timer after the initial `/ping` message. Finally, add some helpful debug logs. Signed-off-by: Christophe Bedard (cherry picked from commit 00a4e99c461e005d093689e1bdbb6b6caa3f5960) Co-authored-by: Christophe Bedard --- test_tracetools/src/test_generic_ping.cpp | 6 +++++- test_tracetools/src/test_generic_pong.cpp | 3 ++- test_tracetools/src/test_ping.cpp | 6 +++++- test_tracetools/src/test_pong.cpp | 3 ++- 4 files changed, 14 insertions(+), 4 deletions(-) diff --git a/test_tracetools/src/test_generic_ping.cpp b/test_tracetools/src/test_generic_ping.cpp index 8ae18f89..79fbfff8 100644 --- a/test_tracetools/src/test_generic_ping.cpp +++ b/test_tracetools/src/test_generic_ping.cpp @@ -41,7 +41,7 @@ class PingNode : public rclcpp::Node pub_ = this->create_generic_publisher( PUB_TOPIC_NAME, "std_msgs/msg/String", - rclcpp::QoS(QUEUE_DEPTH)); + rclcpp::QoS(QUEUE_DEPTH).transient_local()); timer_ = this->create_wall_timer( 500ms, std::bind(&PingNode::timer_callback, this)); @@ -69,7 +69,11 @@ class PingNode : public rclcpp::Node rclcpp::SerializedMessage serialized_msg; serialized_msg.reserve(1024); serializer_->serialize_message(&msg, &serialized_msg); + RCLCPP_INFO(this->get_logger(), "ping"); pub_->publish(serialized_msg); + if (do_only_one_) { + timer_->cancel(); + } } rclcpp::GenericSubscription::SharedPtr sub_; diff --git a/test_tracetools/src/test_generic_pong.cpp b/test_tracetools/src/test_generic_pong.cpp index d6398dca..b7574071 100644 --- a/test_tracetools/src/test_generic_pong.cpp +++ b/test_tracetools/src/test_generic_pong.cpp @@ -32,7 +32,7 @@ class PongNode : public rclcpp::Node sub_ = this->create_generic_subscription( SUB_TOPIC_NAME, "std_msgs/msg/String", - rclcpp::QoS(10), + rclcpp::QoS(10).transient_local(), std::bind(&PongNode::callback, this, std::placeholders::_1)); pub_ = this->create_generic_publisher( PUB_TOPIC_NAME, @@ -55,6 +55,7 @@ class PongNode : public rclcpp::Node rclcpp::SerializedMessage serialized_msg; serialized_msg.reserve(1024); serializer_->serialize_message(&next_msg, &serialized_msg); + RCLCPP_INFO(this->get_logger(), "pong"); pub_->publish(serialized_msg); if (do_only_one_) { rclcpp::shutdown(); diff --git a/test_tracetools/src/test_ping.cpp b/test_tracetools/src/test_ping.cpp index b06a87e5..61951b20 100644 --- a/test_tracetools/src/test_ping.cpp +++ b/test_tracetools/src/test_ping.cpp @@ -38,7 +38,7 @@ class PingNode : public rclcpp::Node std::bind(&PingNode::callback, this, std::placeholders::_1)); pub_ = this->create_publisher( PUB_TOPIC_NAME, - rclcpp::QoS(QUEUE_DEPTH)); + rclcpp::QoS(QUEUE_DEPTH).transient_local()); timer_ = this->create_wall_timer( 500ms, std::bind(&PingNode::timer_callback, this)); @@ -60,7 +60,11 @@ class PingNode : public rclcpp::Node { auto msg = std::make_shared(); msg->data = "some random ping string"; + RCLCPP_INFO(this->get_logger(), "ping"); pub_->publish(*msg); + if (do_only_one_) { + timer_->cancel(); + } } rclcpp::Subscription::SharedPtr sub_; diff --git a/test_tracetools/src/test_pong.cpp b/test_tracetools/src/test_pong.cpp index 5a69cab1..7eaedd53 100644 --- a/test_tracetools/src/test_pong.cpp +++ b/test_tracetools/src/test_pong.cpp @@ -30,7 +30,7 @@ class PongNode : public rclcpp::Node { sub_ = this->create_subscription( SUB_TOPIC_NAME, - rclcpp::QoS(10), + rclcpp::QoS(10).transient_local(), std::bind(&PongNode::callback, this, std::placeholders::_1)); pub_ = this->create_publisher( PUB_TOPIC_NAME, @@ -46,6 +46,7 @@ class PongNode : public rclcpp::Node RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); auto next_msg = std::make_shared(); next_msg->data = "some random pong string"; + RCLCPP_INFO(this->get_logger(), "pong"); pub_->publish(*next_msg); if (do_only_one_) { rclcpp::shutdown();