Open nordmoen opened 7 years ago
I created a minimal example demonstrating my problem here: https://github.com/nordmoen/test_gazebo8/tree/master
The main code that does anything is:
for(int i = 0; i < 5; ++i) {
ROS_INFO("Starting iteration %i", i);
auto sub = nh.subscribe("/gazebo/link_states", 5, callback);
wait.sleep();
sub.shutdown();
ROS_INFO("Ending iteration %i", i);
}
Which result in these results:
In Gazebo 7 (tested with 7.4) the expected output is something like:
[ INFO] [1499083983.423210418, 0.203000000]: Gazebo started. Starting loop
[ INFO] [1499083983.423258111, 0.203000000]: Starting iteration 0
[ INFO] [1499083984.223547626, 1.000000000]: Got link_states!
[ INFO] [1499083985.226454890, 2.000000000]: Got link_states!
[ INFO] [1499083986.233047563, 3.000000000]: Got link_states!
[ INFO] [1499083987.238373358, 4.000000000]: Got link_states!
[ INFO] [1499083988.243084799, 5.000000000]: Got link_states!
[ INFO] [1499083988.460649478, 5.216000000]: Ending iteration 0
[ INFO] [1499083988.460723512, 5.216000000]: Starting iteration 1
[ INFO] [1499083989.246983436, 6.000000000]: Got link_states!
[ INFO] [1499083990.251303354, 7.000000000]: Got link_states!
[ INFO] [1499083991.266260549, 8.000000000]: Got link_states!
[ INFO] [1499083992.271432231, 9.000000000]: Got link_states!
[ INFO] [1499083993.276270854, 10.000000000]: Got link_states!
...
In Gazebo 8 (tested with 8.1.1) the output is instead:
[ INFO] [1499082452.365551220, 0.247000000]: Gazebo started. Starting loop
[ INFO] [1499082452.365563268, 0.247000000]: Starting iteration 0
[ INFO] [1499082453.119217355, 1.000000000]: Got link_states!
[ INFO] [1499082454.120610593, 2.000000000]: Got link_states!
[ INFO] [1499082455.123890395, 3.000000000]: Got link_states!
[ INFO] [1499082456.221480809, 4.001000000]: Got link_states!
[ INFO] [1499082457.217972288, 5.001000000]: Got link_states!
[ INFO] [1499082457.465672239, 5.252000000]: Ending iteration 0
[ INFO] [1499082457.465704627, 5.252000000]: Starting iteration 1
[ INFO] [1499082462.783421969, 10.263000000]: Ending iteration 1
[ INFO] [1499082462.783455855, 10.263000000]: Starting iteration 2
[ INFO] [1499082468.489491249, 15.299000000]: Ending iteration 2
[ INFO] [1499082468.489523642, 15.299000000]: Starting iteration 3
[ INFO] [1499082473.496997661, 20.323000000]: Ending iteration 3
[ INFO] [1499082473.497029367, 20.323000000]: Starting iteration 4
[ INFO] [1499082478.510929082, 25.328000000]: Ending iteration 4
[ INFO] [1499082478.510962179, 25.328000000]: Ending 'test_gazebo8_node'
+1, same issue here when using rostopic echo -n1 multiple times on /gazebo/model_states
. The other topic (link_states) is still being published in the meanwhile.
I added some logging statements and it appears that the counters in gazbo_ros_api_plugin.cpp are being incremented and decremented correctly. Upon second connect of a subscriber (following a disconnect), gazebo::event::Events::ConnectWorldUpdateBegin()
is correctly being called, but it appears to have no effect. The callback function publishModelStates()
does not get invoked subsequently.
Maybe a regression caused by a change in gazebo::event?
+1, it happens for both, but they die independently. Running this:
rostopic echo -n1 /gazebo/model_states
rostopic echo -n1 /gazebo/link_states
gets a message for both, but subsequent calls fail.
+1. Running the following alongside Gazebo helped me work around the issue in the meantime:
rosrun topic_tools relay /gazebo/link_states /link_states
and then subscribe to /link_states instead.
I just updated my source install, gazebo_ros_pkgs
version 2.7.2
, and the problem has vanished. Unfortunately I have not noted the version I upgraded from so I can't tell which commit fixed the issue, but running test_gazebo8
now shows the same behaviour as Gazebo7.
If anyone else can comment as to if the problem is fixed for them and maybe even which version it did and didn't work on we can close this issue.
@nordmoen It seems that you were using ROS Kinetic, right? Because I'm having the same issue with ROS Lunar and Gazebo 8. In my case, I have gazebo8_ros_pkgs
version 2.7.2
.
@eborghi10 I'm using Lunar as well. Recently upgraded to Gazebo 8.1.1
so maybe there is some interaction between gazebo_ros_pkgs
and Gazebo causing this.
I'm using Gazebo 8.4.0
but I found yesterday that I cannot subscribe again to the /gazebo/model_states
topic (as an example) once I call to unregister()
.
Here is the testing I have done on this issue (using @nordmoen's script): gazebo 8.4.0 with gazebo_ros_pkgs 2.7.2 -> fails gazebo 8.4.0 with gazebo_ros_pkgs 2.7.3 -> passes gazebo 8.4.0 with gazebo_ros_pkgs 2.7.2 AGAIN -> fails again
The ppa for lunar should now be at 2.7.3, so I would expect this to be solved by just upgrading. My best guess is that it was solved in 79840bc6ff388, which affects that part of the code and was introduced between 2.7.2 and 2.7.3. Let me know if this is still an issue otherwise I'll close.
I'm having a strange problem in Gazebo8, but not in Gazebo7. In my code I have a simulation loop which will interact with a robot for 10 seconds and then evaluate the behavior of the robot. This loop is performed for many different parameters and needs to be performed many (10 000+) times. To collect data for only the 10 seconds of the given parameters I subscribe to the topic
/gazebo/link_states
and unsubscribe later (by callingshutdown
) when the 10 second evaluation has finished. In Gazebo7 (tested with both Ubuntu and Fedora) this worked perfectly and no problems where detected, but then I had an unrelated problem and needed to upgrade to Gazebo8 on Ubuntu which started to exhibit the bad behavior.If I use
rostopic hz /gazebo/link_states
I can see it being output during the first loop, but then it stops being published. This happens for both/gazebo/link_states
and/gazebo/model_states
and only under Gazebo8.Is there anything wrong with unsubscribing from a topic using
shutdown
? I'm unsure how else best to collect data for only the duration of the evaluation loop.