ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
It's very hard to tell what your program is doing, but I'll give this a shot. I assume you want the latitude and longitude values from one message in your main thread?
There needs to be a thread calling rospy.spin() so that callbacks happen. 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)
#Have rospy.spin() happen on another thread so callbacks can happen
thr = threading.Thread(target=rospy.spin)
thr.daemon = True #make sure spin thread stops when script finishes
thr.start()
#Get the info
ig = InfoGetter()
rospy.Subscriber("/novatel/fix", NavSatFix, ig)
#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}"
2 | No.2 Revision |
It's very hard to tell what your program is doing, but I'll give this a shot. I assume you want the latitude and longitude values from one message in your main thread?
There needs to be a thread calling rospy.spin() so that callbacks happen. 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)
#Have rospy.spin() happen on another thread so callbacks can happen
thr = threading.Thread(target=rospy.spin)
thr.daemon = True #make sure spin thread stops when script finishes
thr.start()
#Get the info
ig = InfoGetter()
rospy.Subscriber("/novatel/fix", NavSatFix, ig)
#Blocks #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}"
3 | No.3 Revision |
It's very hard to tell what your program is doing, but I'll give this a shot. I assume you want the latitude and longitude values from one message in your main thread?
There needs to be a thread calling rospy.spin() so that callbacks happen. 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}"
4 | No.4 Revision |
It's very hard to tell what your program is doing, but I'll give this a shot. 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}"