Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions rclpy/topics/minimal_publisher/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,4 @@ This package contains a few different strategies for creating short nodes that b
The `publisher_old_school` recipe creates a talker node very similar to how it would be done in ROS 1 using rospy.
The `publisher_local_function` recipe shows how to leverage the timers provided by ROS 2 to trigger message publication.
The `publisher_member_function` recipe creates a class MinimalPublisher that sends messages periodically.
The `publisher_member_function_with_wait_for_all_acked` recipe creates a class MinimalPublisher that sends messages and wait for all messages are acknowledged.
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
# Copyright 2025 Sony Group Corporation.
#
# 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 rclpy
from rclpy.duration import Duration
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from std_msgs.msg import String


class MinimalPublisher(Node):

def __init__(self):
super().__init__('minimal_publisher_with_wait_for_all_acked')
reliable_qos = rclpy.qos.QoSProfile(
depth=10,
reliability=rclpy.qos.QoSReliabilityPolicy.RELIABLE)
self.publisher_ = self.create_publisher(String, 'topic', reliable_qos)

self.timer_period = 0.5 # seconds
self.timer = self.create_timer(self.timer_period, self.timer_callback)
self.i = 0
self.max_count = 10

def wait_for_all_acked(self):
self.get_logger().info('Waiting for all messages to be acknowledged...')
acknowledged = self.publisher_.wait_for_all_acked(Duration(seconds=3))
if acknowledged:
self.get_logger().info('All messages acknowledged.')
else:
self.get_logger().warn('Not all messages were acknowledged.')

def timer_callback(self):
if self.i < self.max_count:
msg = String()
msg.data = 'Hello World: %d' % self.i
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1
else:
self.timer.cancel()
self.wait_for_all_acked()
self.i = 0
self.timer.reset()


def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
try:
rclpy.spin(minimal_publisher)
except (KeyboardInterrupt, ExternalShutdownException):
pass
finally:
rclpy.shutdown()


if __name__ == '__main__':
main()
3 changes: 3 additions & 0 deletions rclpy/topics/minimal_publisher/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,9 @@
' examples_rclpy_minimal_publisher.publisher_local_function:main',
'publisher_member_function ='
' examples_rclpy_minimal_publisher.publisher_member_function:main',
'publisher_member_function_with_wait_for_all_acked ='
' examples_rclpy_minimal_publisher.'
'publisher_member_function_with_wait_for_all_acked:main',
],
},
)