Thanks Ken, for the help and the quick even-on-a-Sunday response. Latching seems to work, although I'm not sure why it's applicable. Spinning at the end did not. What I was doing was 'rostopic echo chatter' then running the code I pasted above, with the two lines switched and a spin at the end. rostopic still doesn't print out the message, unless I add latch=True. I could understand it not working if I started rostopic after the code, but saving the message on the server seems irrelevant here. -David!! On Sun, Sep 12, 2010 at 5:56 PM, Ken Conley wrote: > Hi David, > > There are a couple of issues here: > >  1) your program starts and then exits, which means that only > subscribers that are really fast will get the message. Your node needs > to stay up if you want to guarantee that others receive its message >  2) you probably want to enable 'latching', described below > > ROS topics are like tuning into a streaming broadcast -- if you tune > in 15 minutes late, you don't get to see the stat. Imagine you are > streaming data from the camera -- you want to start receiving messages > the most recent one available. > > The fact that you're getting slightly different results is generally > initialization latency. If you put the Publisher init before the call > to init_node(), then the rospy node is able to send this data > immediately when it communicates with the master. If you put the > Publisher init call after init_node(), it has to go back to the > master, which incurs more latency. > > There is a different behavior you can enable with ROS called > 'latching', where a publisher will store the most recently published > message indefinitely and send it to any new subscriber. We often use > this behavior for data that can be static or slowly changing, like > maps. > > See: > http://www.ros.org/wiki/rospy/Overview/Publishers%20and%20Subscribers#rospy.Publisher_initialization > > You probably want to add a rospy.spin() or other sort of delay at the > end as well. > > HTH, > Ken > > On Sun, Sep 12, 2010 at 3:34 PM, David Lu!! wrote: >> Hey all, >> I'm not quite sure if this is a bug, or if it is, where to file it, >> but it took me forever to track down the problem. >> >> Here's my test program based on rospy tutorials. (I'm using C-Turtle >> binaries on 10.04) >> #!/usr/bin/python >> import roslib; roslib.load_manifest('crazy') >> import rospy >> from std_msgs.msg import String >> >> def talker(): >>    pub = rospy.Publisher('chatter', String) >>    rospy.init_node('talker', anonymous=True) >>    str = "hello world" >>    pub.publish(str) >> >> if __name__ == '__main__': >>    try: >>        talker() >>    except rospy.ROSInterruptException: pass >> >> Fairly standard, and it works like you would expect. However, if you >> switch the order of 7th and 8th lines, i.e. >>    rospy.init_node('talker', anonymous=True) >>    pub = rospy.Publisher('chatter', String) >> ...it does NOT publish the message. >> >> However, when I add a sleep(1) command after Publisher line, then it >> works fine. >> >> Is this... >> A) A bug >> B) A situation where I should just sleep >> C) A situation where I should publish the message repeatedly until I'm >> sure it's received. >> >> Thanks, >> -David!! >> _______________________________________________ >> ros-users mailing list >> ros-users@code.ros.org >> https://code.ros.org/mailman/listinfo/ros-users >> > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users >