Skip to content

Commit

Permalink
Fix deprecation warnings
Browse files Browse the repository at this point in the history
Signed-off-by: Jacob Perron <[email protected]>
  • Loading branch information
jacobperron committed May 13, 2019
1 parent 2f2027d commit 394e93e
Show file tree
Hide file tree
Showing 11 changed files with 28 additions and 26 deletions.
2 changes: 1 addition & 1 deletion rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ def __init__(
self.__executor_weakref = None

self._parameter_event_publisher = self.create_publisher(
ParameterEvent, 'parameter_events', qos_profile=qos_profile_parameter_events)
ParameterEvent, 'parameter_events', qos_profile_parameter_events)

with self.handle as capsule:
self._initial_parameters = _rclpy.rclpy_get_node_parameters(Parameter, capsule)
Expand Down
3 changes: 2 additions & 1 deletion rclpy/rclpy/time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,8 @@ def _subscribe_to_clock_topic(self):
self._clock_sub = self._node.create_subscription(
rosgraph_msgs.msg.Clock,
CLOCK_TOPIC,
self.clock_callback
self.clock_callback,
10
)

def attach_node(self, node):
Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_action_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ def __init__(self, node):
Fibonacci.Impl.GetResultService, '/fibonacci/_action/get_result',
self.result_callback)
self.feedback_pub = node.create_publisher(
Fibonacci.Impl.FeedbackMessage, '/fibonacci/_action/feedback')
Fibonacci.Impl.FeedbackMessage, '/fibonacci/_action/feedback', 1)

def goal_callback(self, request, response):
response.accepted = True
Expand Down
7 changes: 5 additions & 2 deletions rclpy/test/test_action_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,12 @@ def __init__(self, node):
self.result_srv = node.create_client(
Fibonacci.Impl.GetResultService, '/fibonacci/_action/get_result')
self.feedback_sub = node.create_subscription(
Fibonacci.Impl.FeedbackMessage, '/fibonacci/_action/feedback', self.feedback_callback)
Fibonacci.Impl.FeedbackMessage,
'/fibonacci/_action/feedback',
self.feedback_callback,
1)
self.status_sub = node.create_subscription(
Fibonacci.Impl.GoalStatusMessage, '/fibonacci/_action/status', self.status_callback)
Fibonacci.Impl.GoalStatusMessage, '/fibonacci/_action/status', self.status_callback, 1)

def reset(self):
self.feedback_msg = None
Expand Down
4 changes: 2 additions & 2 deletions rclpy/test/test_callback_group.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,10 +71,10 @@ def test_create_timer_with_group(self):
self.assertTrue(group.has_entity(tmr2))

def test_create_subscription_with_group(self):
sub1 = self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg))
sub1 = self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 1)
group = ReentrantCallbackGroup()
sub2 = self.node.create_subscription(
BasicTypes, 'chatter', lambda msg: print(msg), callback_group=group)
BasicTypes, 'chatter', lambda msg: print(msg), 1, callback_group=group)

self.assertFalse(group.has_entity(sub1))
self.assertTrue(group.has_entity(sub2))
Expand Down
4 changes: 2 additions & 2 deletions rclpy/test/test_create_while_spinning.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ def tearDown(self):

def test_publish_subscribe(self):
evt = threading.Event()
self.node.create_subscription(BasicTypes, 'foo', lambda msg: evt.set())
pub = self.node.create_publisher(BasicTypes, 'foo')
self.node.create_subscription(BasicTypes, 'foo', lambda msg: evt.set(), 1)
pub = self.node.create_publisher(BasicTypes, 'foo', 1)
pub.publish(BasicTypes())
assert evt.wait(TIMEOUT)

Expand Down
12 changes: 6 additions & 6 deletions rclpy/test/test_destruction.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,16 +71,16 @@ def test_destroy_entities():
timer = node.create_timer(0.1, None)
timer # noqa
assert 1 == len(tuple(node.timers))
pub1 = node.create_publisher(BasicTypes, 'pub1_topic')
pub1 = node.create_publisher(BasicTypes, 'pub1_topic', 1)
assert 2 == len(tuple(node.publishers))
pub2 = node.create_publisher(BasicTypes, 'pub2_topic')
pub2 = node.create_publisher(BasicTypes, 'pub2_topic', 1)
pub2 # noqa
assert 3 == len(tuple(node.publishers))
sub1 = node.create_subscription(
BasicTypes, 'sub1_topic', lambda msg: ...)
BasicTypes, 'sub1_topic', lambda msg: ..., 1)
assert 1 == len(tuple(node.subscriptions))
sub2 = node.create_subscription(
BasicTypes, 'sub2_topic', lambda msg: ...)
BasicTypes, 'sub2_topic', lambda msg: ..., 1)
sub2 # noqa
assert 2 == len(tuple(node.subscriptions))

Expand All @@ -105,7 +105,7 @@ def test_destroy_subscription_asap():
try:
node = rclpy.create_node('test_destroy_subscription_asap', context=context)
try:
sub = node.create_subscription(BasicTypes, 'sub_topic', lambda msg: ...)
sub = node.create_subscription(BasicTypes, 'sub_topic', lambda msg: ..., 1)

# handle valid
with sub.handle:
Expand Down Expand Up @@ -154,7 +154,7 @@ def test_destroy_publisher_asap():
try:
node = rclpy.create_node('test_destroy_publisher_asap', context=context)
try:
pub = node.create_publisher(BasicTypes, 'pub_topic')
pub = node.create_publisher(BasicTypes, 'pub_topic', 1)

# handle valid
with pub.handle:
Expand Down
4 changes: 2 additions & 2 deletions rclpy/test/test_messages.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,11 @@ def tearDownClass(cls):
def test_invalid_string_raises(self):
msg = Strings()
msg.string_value = 'ñu'
pub = self.node.create_publisher(Strings, 'chatter')
pub = self.node.create_publisher(Strings, 'chatter', 1)
with self.assertRaises(UnicodeEncodeError):
pub.publish(msg)

def test_different_type_raises(self):
pub = self.node.create_publisher(BasicTypes, 'chatter')
pub = self.node.create_publisher(BasicTypes, 'chatter', 1)
with self.assertRaises(TypeError):
pub.publish('different message type')
10 changes: 4 additions & 6 deletions rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@
from rclpy.qos import qos_profile_sensor_data
from test_msgs.msg import BasicTypes


TEST_NODE = 'my_node'
TEST_NAMESPACE = '/my_ns'

Expand Down Expand Up @@ -63,7 +62,6 @@ def test_accessors(self):
self.assertEqual(self.node.get_clock().clock_type, ClockType.ROS_TIME)

def test_create_publisher(self):
self.node.create_publisher(BasicTypes, 'chatter')
self.node.create_publisher(BasicTypes, 'chatter', 0)
self.node.create_publisher(BasicTypes, 'chatter', 1)
self.node.create_publisher(BasicTypes, 'chatter', qos_profile_sensor_data)
Expand All @@ -79,7 +77,6 @@ def test_create_publisher(self):
self.node.create_publisher(BasicTypes, 'chatter', 'foo')

def test_create_subscription(self):
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg))
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 0)
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 1)
self.node.create_subscription(
Expand Down Expand Up @@ -108,6 +105,7 @@ def test_create_raw_subscription(self):
BasicTypes,
'raw_subscription_test',
self.raw_subscription_callback,
1,
raw=True
)
basic_types_msg = BasicTypes()
Expand Down Expand Up @@ -216,15 +214,15 @@ def test_count_publishers_subscribers(self):
self.assertEqual(0, self.node.count_publishers(fq_topic_name))
self.assertEqual(0, self.node.count_subscribers(fq_topic_name))

self.node.create_publisher(BasicTypes, short_topic_name)
self.node.create_publisher(BasicTypes, short_topic_name, 1)
self.assertEqual(1, self.node.count_publishers(short_topic_name))
self.assertEqual(1, self.node.count_publishers(fq_topic_name))

self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg))
self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg), 1)
self.assertEqual(1, self.node.count_subscribers(short_topic_name))
self.assertEqual(1, self.node.count_subscribers(fq_topic_name))

self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg))
self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg), 1)
self.assertEqual(2, self.node.count_subscribers(short_topic_name))
self.assertEqual(2, self.node.count_subscribers(fq_topic_name))

Expand Down
4 changes: 2 additions & 2 deletions rclpy/test/test_time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ def tearDown(self):
rclpy.shutdown(context=self.context)

def publish_clock_messages(self):
clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC)
clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC, 1)
cycle_count = 0
time_msg = rosgraph_msgs.msg.Clock()
while rclpy.ok(context=self.context) and cycle_count < 5:
Expand All @@ -59,7 +59,7 @@ def publish_clock_messages(self):
time.sleep(1)

def publish_reversed_clock_messages(self):
clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC)
clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC, 1)
cycle_count = 0
time_msg = rosgraph_msgs.msg.Clock()
while rclpy.ok(context=self.context) and cycle_count < 5:
Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_waitable.py
Original file line number Diff line number Diff line change
Expand Up @@ -349,7 +349,7 @@ def test_waitable_with_timer(self):
def test_waitable_with_subscription(self):
self.waitable = SubscriptionWaitable(self.node)
self.node.add_waitable(self.waitable)
pub = self.node.create_publisher(EmptyMsg, 'test_topic')
pub = self.node.create_publisher(EmptyMsg, 'test_topic', 1)

thr = self.start_spin_thread(self.waitable)
pub.publish(EmptyMsg())
Expand Down

0 comments on commit 394e93e

Please sign in to comment.