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

Publish a message from global scope in python

asked 2016-11-10 05:40:57 -0500

215 gravatar image

updated 2016-11-10 06:15:27 -0500

I am currently Trying to make this rosnode work, but I aren't sure why i am not able to do the first publish in this code, being the pub.publish(String("start")) But able to do the ones in the callback, what is wrong?

#!/usr/bin/env python

import rospy
from std_msgs.msg import Empty
from std_msgs.msg import Int8
from std_msgs.msg import String
import numpy as np

rospy.init_node('Node', anonymous=True)
pub = rospy.Publisher('/status', String, queue_size=1000)
pub.publish(String("start"))

def callback(data):
    print "Message received"
    pub.publish(String("New - status"))

def listener():

    # In ROS, nodes are uniquely named. If two nodes with the same
    # name are launched, the previous one is kicked off. The
    # anonymous=True flag means that rospy will choose a unique
    # name for our 'listener' node so that multiple listeners can
    # run simultaneously.
    rospy.Subscriber('control', Empty, callback)
    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

if __name__ == '__main__':
    print "Running"
    listener()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-11-10 06:20:40 -0500

mgruhler gravatar image

ROS Publishers and scubscribers need a little time to properly register with the master. Thus, this publish goes into nirvana somewhere. If you put a rospy.sleep(2.0) before the first publish, it will work.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-11-10 05:40:57 -0500

Seen: 1,321 times

Last updated: Nov 10 '16