File tree 4 files changed +14
-4
lines changed
4 files changed +14
-4
lines changed Original file line number Diff line number Diff line change @@ -41,7 +41,7 @@ class PingNode : public rclcpp::Node
41
41
pub_ = this ->create_generic_publisher (
42
42
PUB_TOPIC_NAME,
43
43
" std_msgs/msg/String" ,
44
- rclcpp::QoS (QUEUE_DEPTH));
44
+ rclcpp::QoS (QUEUE_DEPTH). transient_local () );
45
45
timer_ = this ->create_wall_timer (
46
46
500ms,
47
47
std::bind (&PingNode::timer_callback, this ));
@@ -69,7 +69,11 @@ class PingNode : public rclcpp::Node
69
69
rclcpp::SerializedMessage serialized_msg;
70
70
serialized_msg.reserve (1024 );
71
71
serializer_->serialize_message (&msg, &serialized_msg);
72
+ RCLCPP_INFO (this ->get_logger (), " ping" );
72
73
pub_->publish (serialized_msg);
74
+ if (do_only_one_) {
75
+ timer_->cancel ();
76
+ }
73
77
}
74
78
75
79
rclcpp::GenericSubscription::SharedPtr sub_;
Original file line number Diff line number Diff line change @@ -32,7 +32,7 @@ class PongNode : public rclcpp::Node
32
32
sub_ = this ->create_generic_subscription (
33
33
SUB_TOPIC_NAME,
34
34
" std_msgs/msg/String" ,
35
- rclcpp::QoS (10 ),
35
+ rclcpp::QoS (10 ). transient_local () ,
36
36
std::bind (&PongNode::callback, this , std::placeholders::_1));
37
37
pub_ = this ->create_generic_publisher (
38
38
PUB_TOPIC_NAME,
@@ -55,6 +55,7 @@ class PongNode : public rclcpp::Node
55
55
rclcpp::SerializedMessage serialized_msg;
56
56
serialized_msg.reserve (1024 );
57
57
serializer_->serialize_message (&next_msg, &serialized_msg);
58
+ RCLCPP_INFO (this ->get_logger (), " pong" );
58
59
pub_->publish (serialized_msg);
59
60
if (do_only_one_) {
60
61
rclcpp::shutdown ();
Original file line number Diff line number Diff line change @@ -38,7 +38,7 @@ class PingNode : public rclcpp::Node
38
38
std::bind (&PingNode::callback, this , std::placeholders::_1));
39
39
pub_ = this ->create_publisher <std_msgs::msg::String>(
40
40
PUB_TOPIC_NAME,
41
- rclcpp::QoS (QUEUE_DEPTH));
41
+ rclcpp::QoS (QUEUE_DEPTH). transient_local () );
42
42
timer_ = this ->create_wall_timer (
43
43
500ms,
44
44
std::bind (&PingNode::timer_callback, this ));
@@ -60,7 +60,11 @@ class PingNode : public rclcpp::Node
60
60
{
61
61
auto msg = std::make_shared<std_msgs::msg::String>();
62
62
msg->data = " some random ping string" ;
63
+ RCLCPP_INFO (this ->get_logger (), " ping" );
63
64
pub_->publish (*msg);
65
+ if (do_only_one_) {
66
+ timer_->cancel ();
67
+ }
64
68
}
65
69
66
70
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
Original file line number Diff line number Diff line change @@ -30,7 +30,7 @@ class PongNode : public rclcpp::Node
30
30
{
31
31
sub_ = this ->create_subscription <std_msgs::msg::String>(
32
32
SUB_TOPIC_NAME,
33
- rclcpp::QoS (10 ),
33
+ rclcpp::QoS (10 ). transient_local () ,
34
34
std::bind (&PongNode::callback, this , std::placeholders::_1));
35
35
pub_ = this ->create_publisher <std_msgs::msg::String>(
36
36
PUB_TOPIC_NAME,
@@ -46,6 +46,7 @@ class PongNode : public rclcpp::Node
46
46
RCLCPP_INFO (this ->get_logger (), " [output] %s" , msg->data .c_str ());
47
47
auto next_msg = std::make_shared<std_msgs::msg::String>();
48
48
next_msg->data = " some random pong string" ;
49
+ RCLCPP_INFO (this ->get_logger (), " pong" );
49
50
pub_->publish (*next_msg);
50
51
if (do_only_one_) {
51
52
rclcpp::shutdown ();
You can’t perform that action at this time.
0 commit comments