Skip to content

Commit 97631f5

Browse files
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 <[email protected]> (cherry picked from commit 00a4e99) Co-authored-by: Christophe Bedard <[email protected]>
1 parent 6a09ad1 commit 97631f5

File tree

4 files changed

+14
-4
lines changed

4 files changed

+14
-4
lines changed

Diff for: test_tracetools/src/test_generic_ping.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ class PingNode : public rclcpp::Node
4141
pub_ = this->create_generic_publisher(
4242
PUB_TOPIC_NAME,
4343
"std_msgs/msg/String",
44-
rclcpp::QoS(QUEUE_DEPTH));
44+
rclcpp::QoS(QUEUE_DEPTH).transient_local());
4545
timer_ = this->create_wall_timer(
4646
500ms,
4747
std::bind(&PingNode::timer_callback, this));
@@ -69,7 +69,11 @@ class PingNode : public rclcpp::Node
6969
rclcpp::SerializedMessage serialized_msg;
7070
serialized_msg.reserve(1024);
7171
serializer_->serialize_message(&msg, &serialized_msg);
72+
RCLCPP_INFO(this->get_logger(), "ping");
7273
pub_->publish(serialized_msg);
74+
if (do_only_one_) {
75+
timer_->cancel();
76+
}
7377
}
7478

7579
rclcpp::GenericSubscription::SharedPtr sub_;

Diff for: test_tracetools/src/test_generic_pong.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ class PongNode : public rclcpp::Node
3232
sub_ = this->create_generic_subscription(
3333
SUB_TOPIC_NAME,
3434
"std_msgs/msg/String",
35-
rclcpp::QoS(10),
35+
rclcpp::QoS(10).transient_local(),
3636
std::bind(&PongNode::callback, this, std::placeholders::_1));
3737
pub_ = this->create_generic_publisher(
3838
PUB_TOPIC_NAME,
@@ -55,6 +55,7 @@ class PongNode : public rclcpp::Node
5555
rclcpp::SerializedMessage serialized_msg;
5656
serialized_msg.reserve(1024);
5757
serializer_->serialize_message(&next_msg, &serialized_msg);
58+
RCLCPP_INFO(this->get_logger(), "pong");
5859
pub_->publish(serialized_msg);
5960
if (do_only_one_) {
6061
rclcpp::shutdown();

Diff for: test_tracetools/src/test_ping.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ class PingNode : public rclcpp::Node
3838
std::bind(&PingNode::callback, this, std::placeholders::_1));
3939
pub_ = this->create_publisher<std_msgs::msg::String>(
4040
PUB_TOPIC_NAME,
41-
rclcpp::QoS(QUEUE_DEPTH));
41+
rclcpp::QoS(QUEUE_DEPTH).transient_local());
4242
timer_ = this->create_wall_timer(
4343
500ms,
4444
std::bind(&PingNode::timer_callback, this));
@@ -60,7 +60,11 @@ class PingNode : public rclcpp::Node
6060
{
6161
auto msg = std::make_shared<std_msgs::msg::String>();
6262
msg->data = "some random ping string";
63+
RCLCPP_INFO(this->get_logger(), "ping");
6364
pub_->publish(*msg);
65+
if (do_only_one_) {
66+
timer_->cancel();
67+
}
6468
}
6569

6670
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;

Diff for: test_tracetools/src/test_pong.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ class PongNode : public rclcpp::Node
3030
{
3131
sub_ = this->create_subscription<std_msgs::msg::String>(
3232
SUB_TOPIC_NAME,
33-
rclcpp::QoS(10),
33+
rclcpp::QoS(10).transient_local(),
3434
std::bind(&PongNode::callback, this, std::placeholders::_1));
3535
pub_ = this->create_publisher<std_msgs::msg::String>(
3636
PUB_TOPIC_NAME,
@@ -46,6 +46,7 @@ class PongNode : public rclcpp::Node
4646
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
4747
auto next_msg = std::make_shared<std_msgs::msg::String>();
4848
next_msg->data = "some random pong string";
49+
RCLCPP_INFO(this->get_logger(), "pong");
4950
pub_->publish(*next_msg);
5051
if (do_only_one_) {
5152
rclcpp::shutdown();

0 commit comments

Comments
 (0)