Re: [ros-users] dynamic_reconfigure in cturtle stuck

Forside
Vedhæftede filer:
Indlæg som e-mail
+ (text/plain)
+ test.patch (text/x-patch)
Slet denne besked
Besvar denne besked
Skribent: User discussions
Dato:  
Til: ros-users
Emne: Re: [ros-users] dynamic_reconfigure in cturtle stuck
On 01/17/2011 08:36 PM, Blaise Gassend wrote:
>> I somehow got dynparam get ... to work once, but i'm not sure what i
>> did, next time i tried it, it got stuck as usual. I tried to run
>> gdb/strace on it and it looks deadlocked waiting on semaphore. I also
>> looked through logs and it seems dead just before subscribing to
>> /dynamic_reconfigure_test_server/parameter_updates. Maybe python2.7 in
>> fedora 14 has something to do with that? The client never gets
>> subscribed> never gets parameter_updates msg> waits forever. Any
>> suggestions how I can debug it further?
> Can you try with python 2.6?
>
> Do other python nodes work well?
>
> Have you inserted prints in the dynamic reconfigure client code to try
> to figure out where it is getting stuck?

My point is getting it working under fedora 14 so python-2.7 is a given.

I was playing around a bit with simple python pub/sub examples and it looks like it is some kind of a race condition between multiple succeeding subscriptions under same
nodehandle/prefix like /a/chatter1, /a/chatter2. It is not limited to dynamic_reconfigure.

It happens with both cpp and python publishers but only with a python subscriber. c++ subscriber always works fine.

I modified src/dynamic_reconfigure/client.py like this
          self._updates_sub      = self._get_subscriber('parameter_updates',...
+        rospy.sleep(1)
          self._descriptions_sub = self._get_subscriber('parameter_descriptions',...


and now it works.

I tested it with talker/listener tutorials modified with attached patch, and it randomly works ok, only with one topic or not at all.

v.
Index: rospy_tutorials/001_talker_listener/talker.py
===================================================================
--- rospy_tutorials/001_talker_listener/talker.py    (revision 12874)
+++ rospy_tutorials/001_talker_listener/talker.py    (working copy)
@@ -42,13 +42,15 @@
 from std_msgs.msg import String


 def talker():
-    pub = rospy.Publisher('chatter', String)
+    pub = rospy.Publisher('/a/chatter', String)
+    pub1 = rospy.Publisher('/a/chatter1', String)
     rospy.init_node('talker', anonymous=True)
     r = rospy.Rate(10) # 10hz
     while not rospy.is_shutdown():
         str = "hello world %s"%rospy.get_time()
         rospy.loginfo(str)
         pub.publish(str)
+        pub1.publish("1 " + str)
         r.sleep()


 if __name__ == '__main__':
Index: rospy_tutorials/001_talker_listener/listener.py
===================================================================
--- rospy_tutorials/001_talker_listener/listener.py    (revision 12874)
+++ rospy_tutorials/001_talker_listener/listener.py    (working copy)
@@ -54,7 +54,8 @@
     # run simultaenously.
     rospy.init_node('listener', anonymous=True)


-    rospy.Subscriber("chatter", String, callback)
+    rospy.Subscriber("/a/chatter", String, callback)
+    rospy.Subscriber("/a/chatter1", String, callback)


     # spin() simply keeps python from exiting until this node is stopped
     rospy.spin()
Index: roscpp_tutorials/talker/talker.cpp
===================================================================
--- roscpp_tutorials/talker/talker.cpp    (revision 12874)
+++ roscpp_tutorials/talker/talker.cpp    (working copy)
@@ -80,7 +80,8 @@
    * buffer up before throwing some away.
    */
 // %Tag(PUBLISHER)%
-  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
+  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("/a/chatter", 1000);
+  ros::Publisher chatter_pub1 = n.advertise<std_msgs::String>("/a/chatter1", 1000);
 // %EndTag(PUBLISHER)%


 // %Tag(LOOP_RATE)%
@@ -119,6 +120,7 @@
      */
 // %Tag(PUBLISH)%
     chatter_pub.publish(msg);
+    chatter_pub1.publish(msg);
 // %EndTag(PUBLISH)%


 // %Tag(SPINONCE)%
Index: roscpp_tutorials/listener/listener.cpp
===================================================================
--- roscpp_tutorials/listener/listener.cpp    (revision 12874)
+++ roscpp_tutorials/listener/listener.cpp    (working copy)
@@ -76,7 +76,8 @@
    * away the oldest ones.
    */
 // %Tag(SUBSCRIBER)%
-  ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
+  ros::Subscriber sub = n.subscribe("/a/chatter", 1000, chatterCallback);
+  ros::Subscriber sub1 = n.subscribe("/a/chatter1", 1000, chatterCallback);
 // %EndTag(SUBSCRIBER)%


/**