Skip to content

Commit

Permalink
Fix deprecation warnings (#334)
Browse files Browse the repository at this point in the history
Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed May 15, 2019
1 parent a64f768 commit d57a917
Show file tree
Hide file tree
Showing 7 changed files with 17 additions and 15 deletions.
2 changes: 1 addition & 1 deletion demo_nodes_py/demo_nodes_py/topics/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
7 changes: 4 additions & 3 deletions demo_nodes_py/demo_nodes_py/topics/listener_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)
Expand All @@ -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

Expand Down
1 change: 1 addition & 0 deletions demo_nodes_py/demo_nodes_py/topics/listener_serialized.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_py/demo_nodes_py/topics/talker.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
7 changes: 4 additions & 3 deletions demo_nodes_py/demo_nodes_py/topics/talker_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)
Expand Down Expand Up @@ -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

Expand Down
5 changes: 2 additions & 3 deletions topic_monitor/topic_monitor/scripts/data_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand All @@ -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')
Expand All @@ -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))
Expand Down
8 changes: 4 additions & 4 deletions topic_monitor/topic_monitor/scripts/topic_monitor.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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 = \
Expand Down

0 comments on commit d57a917

Please sign in to comment.