Skip to content

Commit

Permalink
Make test_tracetools ping pubs/subs transient_local (#125)
Browse files Browse the repository at this point in the history
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]>
  • Loading branch information
christophebedard committed Jul 4, 2024
1 parent 8d898b5 commit 00a4e99
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 4 deletions.
6 changes: 5 additions & 1 deletion test_tracetools/src/test_generic_ping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down Expand Up @@ -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_;
Expand Down
3 changes: 2 additions & 1 deletion test_tracetools/src/test_generic_pong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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();
Expand Down
6 changes: 5 additions & 1 deletion test_tracetools/src/test_ping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class PingNode : public rclcpp::Node
std::bind(&PingNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
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));
Expand All @@ -60,7 +60,11 @@ class PingNode : public rclcpp::Node
{
auto msg = std::make_shared<std_msgs::msg::String>();
msg->data = "some random ping string";
RCLCPP_INFO(this->get_logger(), "ping");
pub_->publish(*msg);
if (do_only_one_) {
timer_->cancel();
}
}

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
Expand Down
3 changes: 2 additions & 1 deletion test_tracetools/src/test_pong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class PongNode : public rclcpp::Node
{
sub_ = this->create_subscription<std_msgs::msg::String>(
SUB_TOPIC_NAME,
rclcpp::QoS(10),
rclcpp::QoS(10).transient_local(),
std::bind(&PongNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
PUB_TOPIC_NAME,
Expand All @@ -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<std_msgs::msg::String>();
next_msg->data = "some random pong string";
RCLCPP_INFO(this->get_logger(), "pong");
pub_->publish(*next_msg);
if (do_only_one_) {
rclcpp::shutdown();
Expand Down

0 comments on commit 00a4e99

Please sign in to comment.