ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

How to return an array from my subscriber function

asked 2015-08-13 12:20:02 -0500

negotiator14 gravatar image

updated 2015-08-13 13:36:48 -0500

I am trying to return an array that contains a latitude and a longitude from a subscriber that I wrote. What I am trying to do is have some type of global variable and when infoGetter() is called, go to the callback function, run once, set new values from the /novatel/fix topic to my latitude and longitude variables and return them in an array once we are back in the infoGetter function. The array is sent to another program so I made my subscriber into a function. It is only supposed to run once in my other program and return those values. Is it possible to do what I am trying to do? What am I missing? Here's my subscriber function:

#!/usr/bin/env python
import rospy
from sensor_msgs.msg import NavSatFix
#from RetreiveFiles import whatTheHell
latitude = 0
longitude = 0
ra = [0,0] 

def callback(data):
   rospy.loginfo("Longitude: %f, Latitude %f" % (data.longitude, data.latitude))
   global latitude
   global longitude 
   latitude = data.latitude
   longitude = data.longitude
   #whatTheHell(latitude, longitude)


def infoGetter(): 
    rospy.init_node('infoGetter', anonymous=True)
    rospy.Subscriber("/novatel/fix", NavSatFix, callback)
    #rospy.spin()
    global latitude
    global longitude
    global ra
    pritn ra
    ra[0] = latitude 
    ra[1] = longitude 
    return ra
"""if __name__ == '__main__':
    infoGetter() """
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2015-08-13 13:23:09 -0500

sloretz gravatar image

updated 2015-08-13 14:21:36 -0500

I assume you want the latitude and longitude values from one message in your main thread?

You can wait on a result from the subscriber using a threading.Event object. The "InfoGetter" is better contained in a class than global variables and a function. Here is working code.

import rospy
from sensor_msgs.msg import NavSatFix
import threading


class InfoGetter(object):
    def __init__(self):
        #event that will block until the info is received
        self._event = threading.Event()
        #attribute for storing the rx'd message
        self._msg = None

    def __call__(self, msg):
        #Uses __call__ so the object itself acts as the callback
        #save the data, trigger the event
        self._msg = msg
        self._event.set()

    def get_msg(self, timeout=None):
        """Blocks until the data is rx'd with optional timeout
        Returns the received message
        """
        self._event.wait(timeout)
        return self._msg

if __name__ == '__main__':
    rospy.init_node('infoGetter', anonymous=True)
    #Get the info
    ig = InfoGetter()
    rospy.Subscriber("/novatel/fix", NavSatFix, ig)
    #ig.get_msg() Blocks until message is received
    msg = ig.get_msg()
    print msg

You can test that this code works by starting a roscore, running this script, and executing the following command

rostopic pub /novatel/fix sensor_msgs/NavSatFix "{latitude: 4.0, longitude: 5.0}"
edit flag offensive delete link more

Comments

1

You might want to read through the rospy tutorials again as there's a bit of important incorrect info here. First, in rospy, the only thing spin does is block until the node is shutdown. It is not required for callbacks to happen. Second, rospy.Subscriber does not block.

Dan Lazewatsky gravatar image Dan Lazewatsky  ( 2015-08-13 13:36:06 -0500 )edit

Thanks for the comment, Dan. I checked and you're correct that rospy.spin is not responsible for calling callbacks, my mistake. I've removed the extra thread from the script. Of course subscriber doesn't block, but ig.get_msg() does. I've edited the comment to clarify.

sloretz gravatar image sloretz  ( 2015-08-13 13:51:22 -0500 )edit

Why exactly did you use a threading event object?

lffox gravatar image lffox  ( 2017-03-30 15:54:44 -0500 )edit

@lffox The subscriber callback happens asynchronously in another python thread. The threading.Event blocks the main thread until a message is received. This unusual, but the question seems to ask for a way to block until the first message is received.

sloretz gravatar image sloretz  ( 2017-03-30 16:35:52 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-08-13 12:20:02 -0500

Seen: 2,234 times

Last updated: Aug 13 '15