diff --git a/demo_nodes_py/demo_nodes_py/topics/listener.py b/demo_nodes_py/demo_nodes_py/topics/listener.py index c2b4aadd2..b55c4dcdf 100644 --- a/demo_nodes_py/demo_nodes_py/topics/listener.py +++ b/demo_nodes_py/demo_nodes_py/topics/listener.py @@ -22,7 +22,7 @@ class Listener(Node): def __init__(self): super().__init__('listener') - self.sub = self.create_subscription(String, 'chatter', self.chatter_callback) + self.sub = self.create_subscription(String, 'chatter', self.chatter_callback, 10) def chatter_callback(self, msg): self.get_logger().info('I heard: [%s]' % msg.data) diff --git a/demo_nodes_py/demo_nodes_py/topics/listener_qos.py b/demo_nodes_py/demo_nodes_py/topics/listener_qos.py index 02d5592c7..9749962e1 100644 --- a/demo_nodes_py/demo_nodes_py/topics/listener_qos.py +++ b/demo_nodes_py/demo_nodes_py/topics/listener_qos.py @@ -17,7 +17,8 @@ import rclpy from rclpy.node import Node -from rclpy.qos import qos_profile_default, qos_profile_sensor_data +from rclpy.qos import qos_profile_sensor_data +from rclpy.qos import QoSProfile from rclpy.qos import QoSReliabilityPolicy from std_msgs.msg import String @@ -32,7 +33,7 @@ def __init__(self, qos_profile): else: self.get_logger().info('Best effort listener') self.sub = self.create_subscription( - String, 'chatter', self.chatter_callback, qos_profile=qos_profile) + String, 'chatter', self.chatter_callback, qos_profile) def chatter_callback(self, msg): self.get_logger().info('I heard: [%s]' % msg.data) @@ -54,7 +55,7 @@ def main(argv=sys.argv[1:]): rclpy.init(args=args.argv) if args.reliable: - custom_qos_profile = qos_profile_default + custom_qos_profile = QoSProfile(depth=10) else: custom_qos_profile = qos_profile_sensor_data diff --git a/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py b/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py index c29840d54..723f1ec84 100644 --- a/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py +++ b/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py @@ -26,6 +26,7 @@ def __init__(self): String, 'chatter', self.listener_callback, + 10, raw=True) # We're subscribing to the serialized bytes, not std_msgs.msg.String def listener_callback(self, msg): diff --git a/demo_nodes_py/demo_nodes_py/topics/talker.py b/demo_nodes_py/demo_nodes_py/topics/talker.py index 355b22a4c..1a8c1a970 100644 --- a/demo_nodes_py/demo_nodes_py/topics/talker.py +++ b/demo_nodes_py/demo_nodes_py/topics/talker.py @@ -23,7 +23,7 @@ class Talker(Node): def __init__(self): super().__init__('talker') self.i = 0 - self.pub = self.create_publisher(String, 'chatter') + self.pub = self.create_publisher(String, 'chatter', 10) timer_period = 1.0 self.tmr = self.create_timer(timer_period, self.timer_callback) diff --git a/demo_nodes_py/demo_nodes_py/topics/talker_qos.py b/demo_nodes_py/demo_nodes_py/topics/talker_qos.py index c57446e52..370ab71a6 100644 --- a/demo_nodes_py/demo_nodes_py/topics/talker_qos.py +++ b/demo_nodes_py/demo_nodes_py/topics/talker_qos.py @@ -17,7 +17,8 @@ import rclpy from rclpy.node import Node -from rclpy.qos import qos_profile_default, qos_profile_sensor_data +from rclpy.qos import qos_profile_sensor_data +from rclpy.qos import QoSProfile from rclpy.qos import QoSReliabilityPolicy from std_msgs.msg import String @@ -32,7 +33,7 @@ def __init__(self, qos_profile): self.get_logger().info('Reliable talker') else: self.get_logger().info('Best effort talker') - self.pub = self.create_publisher(String, 'chatter', qos_profile=qos_profile) + self.pub = self.create_publisher(String, 'chatter', qos_profile) timer_period = 1.0 self.tmr = self.create_timer(timer_period, self.timer_callback) @@ -61,7 +62,7 @@ def main(argv=sys.argv[1:]): rclpy.init(args=args.argv) if args.reliable: - custom_qos_profile = qos_profile_default + custom_qos_profile = QoSProfile(depth=10) else: custom_qos_profile = qos_profile_sensor_data diff --git a/topic_monitor/topic_monitor/scripts/data_publisher.py b/topic_monitor/topic_monitor/scripts/data_publisher.py index de77104bf..216ae0e4a 100755 --- a/topic_monitor/topic_monitor/scripts/data_publisher.py +++ b/topic_monitor/topic_monitor/scripts/data_publisher.py @@ -63,7 +63,7 @@ def main(): node = rclpy.create_node('%s_pub' % topic_name) node_logger = node.get_logger() - qos_profile = QoSProfile() + qos_profile = QoSProfile(depth=args.depth) if args.best_effort: node_logger.info('Reliability: best effort') @@ -80,7 +80,6 @@ def main(): qos_profile.history = QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST node_logger.info('Depth: {0}'.format(args.depth)) - qos_profile.depth = args.depth if args.transient_local: node_logger.info('Durability: transient local') @@ -90,7 +89,7 @@ def main(): qos_profile.durability = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_VOLATILE data_pub = node.create_publisher( - Header, topic_name, qos_profile=qos_profile) + Header, topic_name, qos_profile) node_logger.info('Publishing on topic: {0}'.format(topic_name)) node_logger.info('Payload size: {0}'.format(args.payload_size)) diff --git a/topic_monitor/topic_monitor/scripts/topic_monitor.py b/topic_monitor/topic_monitor/scripts/topic_monitor.py index 45480f49c..6255ad077 100755 --- a/topic_monitor/topic_monitor/scripts/topic_monitor.py +++ b/topic_monitor/topic_monitor/scripts/topic_monitor.py @@ -20,7 +20,7 @@ import rclpy import rclpy.logging -from rclpy.qos import qos_profile_default +from rclpy.qos import QoSProfile from rclpy.qos import QoSReliabilityPolicy from std_msgs.msg import Float32, Header @@ -132,7 +132,7 @@ def add_monitored_topic( topic_type, topic_name, functools.partial(monitored_topic.topic_data_callback, logger_=node_logger), - qos_profile=qos_profile) + qos_profile) assert sub # prevent unused warning # Create a timer for maintaining the expected value received on the topic @@ -156,7 +156,7 @@ def add_monitored_topic( node.get_logger().info( 'Publishing reception rate on topic: %s' % reception_rate_topic_name) reception_rate_publisher = node.create_publisher( - Float32, reception_rate_topic_name) + Float32, reception_rate_topic_name, 10) with self.monitored_topics_lock: monitored_topic.expected_value_timer = expected_value_timer @@ -349,7 +349,7 @@ def run_topic_listening(node, topic_monitor, options): is_new_topic = topic_name and topic_name not in topic_monitor.monitored_topics if is_new_topic: # Register new topic with the monitor - qos_profile = qos_profile_default + qos_profile = QoSProfile(depth=10) qos_profile.depth = QOS_DEPTH if topic_info['reliability'] == 'best_effort': qos_profile.reliability = \