Skip to content

Commit

Permalink
make every rospy test assign Subscriber to a variable- think this is …
Browse files Browse the repository at this point in the history
…needed but not sure
  • Loading branch information
lucasw committed Dec 31, 2023
1 parent 04b3250 commit cc267f0
Show file tree
Hide file tree
Showing 14 changed files with 19 additions and 18 deletions.
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/numpy_msg.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
from rospy.numpy_msg import numpy_msg
rospy.init_node('mynode')
rospy.Subscriber("mytopic", numpy_msg(TopicType)
sub = rospy.Subscriber("mytopic", numpy_msg(TopicType)
Publisher example::
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/rosconsole.py
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ def __init__(self, options):
self._level_string_map = {getattr(Log, level): self._stringify(level) for level in self.LEVEL_COLOR.keys()}

callback = self._once_callback if options.once else self._callback
rospy.Subscriber(options.topic, Log, callback)
self._sub = rospy.Subscriber(options.topic, Log, callback)

def _stringify(self, level):
string = level.ljust(RosConsoleEcho.LEVEL_MAX_LENGTH)
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/test_nodes/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ def listener():
# run simultaneously.
rospy.init_node('listener', anonymous=True)

rospy.Subscriber("chatter", String, callback)
sub = rospy.Subscriber("chatter", String, callback)

# spin() simply keeps python from exiting until this node is stopped
rospy.spin()
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/nodes/listener_once.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ def callback(data):
def listener():
rospy.init_node('listener', anonymous=True)
rospy.sleep(rospy.get_param('delay', 0.0))
rospy.Subscriber("chatter", String, callback)
sub = rospy.Subscriber("chatter", String, callback)
rospy.spin()


Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/nodes/listenerpublisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ def callback(data):

def listener():
rospy.init_node("listenerpublisher")
rospy.Subscriber("chatter", String, callback)
sub = rospy.Subscriber("chatter", String, callback)
rospy.spin()

if __name__ == '__main__':
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/nodes/listenerpublisher_embed.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ def callback(data):

def listener():
rospy.init_node("listenerpublisher_embed")
rospy.Subscriber("chatter", EmbedTest, callback)
sub = rospy.Subscriber("chatter", EmbedTest, callback)
rospy.spin()

if __name__ == '__main__':
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/rostest/test_embed_msg.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ def test_embed_msg(self):

print("Publishing to ", PUBTOPIC)
pub = rospy.Publisher(PUBTOPIC, MSG, queue_size=0)
rospy.Subscriber(LPTOPIC, MSG, self._test_embed_msg_callback)
sub = rospy.Subscriber(LPTOPIC, MSG, self._test_embed_msg_callback)

# publish about 10 messages for fun
import random
Expand Down
8 changes: 4 additions & 4 deletions test/test_rospy/test/rostest/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,10 +72,10 @@ def test_node():
header_out = rospy.Publisher("test_header_out", test_rosmaster.msg.TestHeader, queue_size=0)

#required subs
rospy.Subscriber("test_string_in", test_rosmaster.msg.TestString, chain_callback(string_out))
rospy.Subscriber("test_primitives_in", test_rosmaster.msg.TestPrimitives, chain_callback(primitives_out))
rospy.Subscriber("test_arrays_in", test_rosmaster.msg.TestArrays, chain_callback(arrays_out))
rospy.Subscriber("test_header_in", test_rosmaster.msg.TestHeader, chain_callback(header_out))
sub0 = rospy.Subscriber("test_string_in", test_rosmaster.msg.TestString, chain_callback(string_out))
sub1 = rospy.Subscriber("test_primitives_in", test_rosmaster.msg.TestPrimitives, chain_callback(primitives_out))
sub2 = rospy.Subscriber("test_arrays_in", test_rosmaster.msg.TestArrays, chain_callback(arrays_out))
sub3 = rospy.Subscriber("test_header_in", test_rosmaster.msg.TestHeader, chain_callback(header_out))

# subscription with no publisher
probe_in = rospy.Subscriber("probe_topic", test_rosmaster.msg.TestString)
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/rostest/test_on_shutdown.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ def callback(self, data):
self.success = True

def test_notify(self):
rospy.Subscriber("chatter", String, self.callback)
sub = rospy.Subscriber("chatter", String, self.callback)
rospy.init_node(NAME, anonymous=True)
timeout_t = time.time() + 10.0*1000 #10 seconds
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/rostest/test_pubsub_order.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ def test_subscriber_first(self):

print("Publishing to ", PUBTOPIC)
pub = rospy.Publisher(PUBTOPIC, MSG, queue_size=0)
rospy.Subscriber(LPTOPIC, MSG, self._test_subscriber_first_callback)
sub = rospy.Subscriber(LPTOPIC, MSG, self._test_subscriber_first_callback)

# publish about 10 messages for fun
import random
Expand Down
2 changes: 1 addition & 1 deletion tools/rosnode/test_nodes/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ def listener():
# run simultaneously.
rospy.init_node('listener', anonymous=True)

rospy.Subscriber("chatter", String, callback)
sub = rospy.Subscriber("chatter", String, callback)

# spin() simply keeps python from exiting until this node is stopped
rospy.spin()
Expand Down
4 changes: 2 additions & 2 deletions tools/rostopic/src/rostopic/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -310,9 +310,9 @@ def _rostopic_hz(topics, window_size=-1, filter_expr=None, use_wtime=False, tcp_
# may parameterize this in the future
if filter_expr is not None:
# have to subscribe with topic_type
rospy.Subscriber(real_topic, msg_class, rt.callback_hz, callback_args=topic, tcp_nodelay=tcp_nodelay)
sub = rospy.Subscriber(real_topic, msg_class, rt.callback_hz, callback_args=topic, tcp_nodelay=tcp_nodelay)
else:
rospy.Subscriber(real_topic, rospy.AnyMsg, rt.callback_hz, callback_args=topic, tcp_nodelay=tcp_nodelay)
sub = rospy.Subscriber(real_topic, rospy.AnyMsg, rt.callback_hz, callback_args=topic, tcp_nodelay=tcp_nodelay)
print("subscribed to [%s]" % real_topic)

if rospy.get_param('use_sim_time', False):
Expand Down
3 changes: 2 additions & 1 deletion tools/rostopic/test/check_rostopic_command_line_online.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,9 @@ def test_rostopic(self):
topics = self.topics
cmd = self.cmd

subs = {}
for i, t in enumerate(topics):
rospy.Subscriber(t, std_msgs.msg.String, self.callback, i)
subs[i] = rospy.Subscriber(t, std_msgs.msg.String, self.callback, i)

timeout_t = time.time() + 10.0
while time.time() < timeout_t and set(topics) != set(self.msgs.keys()):
Expand Down
2 changes: 1 addition & 1 deletion utilities/roswtf/src/roswtf/graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ def topic_timestamp_drift(ctx, t):
#TODO: get msg_class, if msg_class has header, receive a message
# and compare its time to ros time
if 0:
rospy.Subscriber(t, msg_class)
sub = rospy.Subscriber(t, msg_class)

#TODO: these are mainly future enhancements. It's unclear to me whether or not this will be
#useful as most of the generic rules are capable of targeting these problems as well.
Expand Down

0 comments on commit cc267f0

Please sign in to comment.