Gazebo aborts with boost::lock_error when adding a model with a GPU ray sensor
I tried to add a GPU ray sensor to our Hector robot model using ROS hydro and Gazebo 1.8.6 from the ROS package repositories.
This is the SDF description of the sensor:
<sensor name="laser1" type="gpu_ray">
<always_on>true</always_on>
<update_rate>40</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>1081</samples>
<resolution>1</resolution>
<min_angle>135</min_angle>
<max_angle>-135</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_gpu_laser.so" name="gazebo_ros_laser1_controller">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>40</updateRate>
<topicName>laser1/scan</topicName>
<frameName>laser1_frame</frameName>
</plugin>
</sensor>
When the model is loaded, gazebo crashes with the following error message:
gzserver: /usr/include/boost/thread/pthread/mutex.hpp:61: void boost::mutex::unlock(): Assertion `!pthread_mutex_unlock(&m)' failed.
Aborted (core dumped)
I also tried to add the sensor without the plugin and even without the parameters, but this does not help either. I then compiled gazebo (branch default) and gazebo_ros_pkgs (branch hydro-devel) from source with debug information to be able to create a stack trace. The lock_error seems to happen somewhere in the callback queue of the gazebo_ros_api_plugin:
#0 0x00007f94e6066425 in __GI_raise (sig=<optimized out>) at ../nptl/sysdeps/unix/sysv/linux/raise.c:64
#1 0x00007f94e6069b8b in __GI_abort () at abort.c:91
#2 0x00007f94e66bc69d in __gnu_cxx::__verbose_terminate_handler() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#3 0x00007f94e66ba846 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#4 0x00007f94e66ba873 in std::terminate() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#5 0x00007f94e66ba96e in __cxa_throw () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#6 0x0000000000475c7a in boost::throw_exception<boost::lock_error> (e=...) at /usr/include/boost/throw_exception.hpp:61
#7 0x00007f94d14c4538 in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/hydro/lib/libroscpp.so
#8 0x00007f94d1931e33 in gazebo::GazeboRosApiPlugin::gazeboQueueThread (this=0x268bce0) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_ros/src/gazebo_ros_api_plugin.cpp:205
#9 0x00007f94d19a5c80 in boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>::operator() (this=0x27c4328, p=0x268bce0) at /usr/include/boost/bind/mem_fn_template.hpp:49
#10 0x00007f94d19a3708 in boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> >::operator()<boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list0> (this=0x27c4338, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#11 0x00007f94d1998d89 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> > >::operator() (this=0x27c4328)
at /usr/include/boost/bind/bind_template.hpp:20
#12 0x00007f94d19bf3ba in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> > > >::run (this=0x27c41a0)
at /usr/include/boost/thread/detail/thread.hpp:61
#13 0x00007f94e6d7ace9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#14 0x00007f94e7909e9a in start_thread (arg=0x7f94a7fff700) at pthread_create.c:308
#15 0x00007f94e6123ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#16 0x0000000000000000 in ?? ()
I am not sure how this is related to the gpu_ray sensor, but with a standard ray sensor and the libgazebo_ros_laser plugin the model is spawned successfully.
I am using a Dell Latitude E6400 laptop with an Nvidia Quadro NVS 160M card running Ubuntu 12.04 (64 bit).
Does anybody has an idea or are there any known issues with GPU ray sensors in Gazebo? What speedup can be expected? Since Gazebo 1.0 (fuerte) simulation runs really slow compared to earlier versions (in electric) and we are happy about every possibility to come close to real-time again.
Update:
I found an error in the SDF parameters for the GPU ray sensor as stated above. In earlier versions we set min_angle
to 135
and max_angle
to -135
for the normal ray sensor for some reasons and I copied these parameters to new description. The GpuRaySensor checks these angles and throws if max_angle
- min_angle
is negative. Also newer versions of Gazebo require these angles to be specified in radians instead of degress. This SDF errors cause the server to abort and to destroy all plugins before the error message is printed to the screen. I assume the lock_error occurs as the callback queue object is deleted by thread 1 without properly terminating the thread 10 before, that calls callAvailable()
in a queue.
Here is the full stack trace of all threads as requested by @nkoenig:
Thread 21 (Thread 0x7f8b1650b700 (LWP 10069)):
#0 __lll_lock_wait () at ../nptl/sysdeps/unix/sysv/linux/x86_64/lowlevellock.S:132
#1 0x00007f8b7371d065 in _L_lock_858 () from /lib/x86_64-linux-gnu/libpthread.so.0
#2 0x00007f8b7371ceba in __pthread_mutex_lock (mutex=0x7f8b5f3e82e0) at pthread_mutex_lock.c:61
#3 0x00007f8b5f1df985 in ros::package::command(std::string const&) () from /opt/ros/hydro/lib/libroslib.so
#4 0x00007f8b5f1dfc25 in ros::package::command(std::string const&, std::vector<std::string, std::allocator<std::string> >&) () from /opt/ros/hydro/lib/libroslib.so
#5 0x00007f8b5f1e016f in ?? () from /opt/ros/hydro/lib/libroslib.so
#6 0x00007f8b5f1e0b4d in ros::package::getPlugins(std::string const&, std::string const&, std::vector<std::string, std::allocator<std::string> >&) () from /opt/ros/hydro/lib/libroslib.so
#7 0x00007f8b17dd5de1 in pluginlib::ClassLoader<image_transport::SubscriberPlugin>::determineAvailableClasses() () from /opt/ros/hydro/lib/libimage_transport.so
#8 0x00007f8b17dd62cf in pluginlib::ClassLoader<image_transport::SubscriberPlugin>::ClassLoader(std::string, std::string, std::string) () from /opt/ros/hydro/lib/libimage_transport.so
#9 0x00007f8b17dd6765 in boost::shared_ptr<pluginlib::ClassLoader<image_transport::SubscriberPlugin> > boost::make_shared<pluginlib::ClassLoader<image_transport::SubscriberPlugin>, char [16], char [34]>(char const (&) [16], char const (&) [34]) () from /opt/ros/hydro/lib/libimage_transport.so
#10 0x00007f8b17dce2f5 in image_transport::ImageTransport::ImageTransport(ros::NodeHandle const&) () from /opt/ros/hydro/lib/libimage_transport.so
#11 0x00007f8b1c740767 in gazebo::GazeboRosCameraUtils::LoadThread (this=0x3d4f248) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_plugins/src/gazebo_ros_camera_utils.cpp:267
#12 0x00007f8b1c752262 in boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>::operator() (this=0x3d4ff78, p=0x3d4f248) at /usr/include/boost/bind/mem_fn_template.hpp:49
#13 0x00007f8b1c753c38 in boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosCameraUtils*> >::operator()<boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>, boost::_bi::list0> (this=0x3d4ff88, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#14 0x00007f8b1c753be7 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosCameraUtils*> > >::operator() (this=0x3d4ff78)
at /usr/include/boost/bind/bind_template.hpp:20
#15 0x00007f8b1c7536fa in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosCameraUtils*> > > >::run (this=0x3d4fdf0)
at /usr/include/boost/thread/detail/thread.hpp:61
#16 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#17 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1650b700) at pthread_create.c:308
#18 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#19 0x0000000000000000 in ?? ()
Thread 20 (Thread 0x7f8b1718a700 (LWP 10068)):
#0 0x00007f8b71f310a7 in munmap () at ../sysdeps/unix/syscall-template.S:82
#1 0x00007f8b71ebcfc2 in _IO_setb (f=0x7f8b2c190950, b=0x0, eb=<optimized out>, a=<optimized out>) at genops.c:406
#2 0x00007f8b71ebb31e in _IO_new_file_close_it (fp=0x7f8b2c190950) at fileops.c:190
#3 0x00007f8b71eaf840 in _IO_new_fclose (fp=0x7f8b2c190950) at iofclose.c:62
#4 0x00007f8b712f3f52 in TiXmlDocument::LoadFile(char const*, TiXmlEncoding) () from /usr/lib/libtinyxml.so.2.6.2
#5 0x00007f8b5ed76087 in rospack::Rosstackage::loadManifest(rospack::Stackage*) () from /opt/ros/hydro/lib/librospack.so
#6 0x00007f8b5ed7af91 in rospack::Rosstackage::addStackage(std::string const&) () from /opt/ros/hydro/lib/librospack.so
#7 0x00007f8b5ed7b2a2 in rospack::Rosstackage::readCache() () from /opt/ros/hydro/lib/librospack.so
#8 0x00007f8b5ed7de52 in rospack::Rosstackage::crawl(std::vector<std::string, std::allocator<std::string> >, bool) () from /opt/ros/hydro/lib/librospack.so
#9 0x00007f8b5ed8dd45 in rospack::rospack_run(int, char**, rospack::Rosstackage&, std::string&) () from /opt/ros/hydro/lib/librospack.so
#10 0x00007f8b5ed8964b in rospack::ROSPack::run(int, char**) () from /opt/ros/hydro/lib/librospack.so
#11 0x00007f8b5ed89958 in rospack::ROSPack::run(std::string const&) () from /opt/ros/hydro/lib/librospack.so
#12 0x00007f8b5f1df9a6 in ros::package::command(std::string const&) () from /opt/ros/hydro/lib/libroslib.so
#13 0x00007f8b5f1dfc25 in ros::package::command(std::string const&, std::vector<std::string, std::allocator<std::string> >&) () from /opt/ros/hydro/lib/libroslib.so
#14 0x00007f8b5f1e016f in ?? () from /opt/ros/hydro/lib/libroslib.so
#15 0x00007f8b5f1e0b4d in ros::package::getPlugins(std::string const&, std::string const&, std::vector<std::string, std::allocator<std::string> >&) () from /opt/ros/hydro/lib/libroslib.so
#16 0x00007f8b17dd5de1 in pluginlib::ClassLoader<image_transport::SubscriberPlugin>::determineAvailableClasses() () from /opt/ros/hydro/lib/libimage_transport.so
#17 0x00007f8b17dd62cf in pluginlib::ClassLoader<image_transport::SubscriberPlugin>::ClassLoader(std::string, std::string, std::string) () from /opt/ros/hydro/lib/libimage_transport.so
#18 0x00007f8b17dd6765 in boost::shared_ptr<pluginlib::ClassLoader<image_transport::SubscriberPlugin> > boost::make_shared<pluginlib::ClassLoader<image_transport::SubscriberPlugin>, char [16], char [34]>(char const (&) [16], char const (&) [34]) () from /opt/ros/hydro/lib/libimage_transport.so
#19 0x00007f8b17dce2f5 in image_transport::ImageTransport::ImageTransport(ros::NodeHandle const&) () from /opt/ros/hydro/lib/libimage_transport.so
#20 0x00007f8b1c740767 in gazebo::GazeboRosCameraUtils::LoadThread (this=0x3c43c98) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_plugins/src/gazebo_ros_camera_utils.cpp:267
#21 0x00007f8b1c752262 in boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>::operator() (this=0x3c44708, p=0x3c43c98) at /usr/include/boost/bind/mem_fn_template.hpp:49
#22 0x00007f8b1c753c38 in boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosCameraUtils*> >::operator()<boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>, boost::_bi::list0> (this=0x3c44718, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#23 0x00007f8b1c753be7 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosCameraUtils*> > >::operator() (this=0x3c44708)
at /usr/include/boost/bind/bind_template.hpp:20
#24 0x00007f8b1c7536fa in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosCameraUtils>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosCameraUtils*> > > >::run (this=0x3c44580)
at /usr/include/boost/thread/detail/thread.hpp:61
#25 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#26 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1718a700) at pthread_create.c:308
#27 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#28 0x0000000000000000 in ?? ()
Thread 19 (Thread 0x7f8b5fe11700 (LWP 9846)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b750fbf1c in boost::condition_variable::wait (this=0x6c1320, m=...) at /usr/include/boost/thread/pthread/condition_variable.hpp:53
#2 0x00007f8b750f7a4b in gazebo::common::ModelDatabase::UpdateModelCache (this=0x6c1240, _fetchImmediately=false) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/ModelDatabase.cc:274
#3 0x00007f8b7510c0a1 in boost::_mfi::mf1<void, gazebo::common::ModelDatabase, bool>::operator() (this=0x1030e58, p=0x6c1240, a1=false) at /usr/include/boost/bind/mem_fn_template.hpp:165
#4 0x00007f8b7510b505 in boost::_bi::list2<boost::_bi::value<gazebo::common::ModelDatabase*>, boost::_bi::value<bool> >::operator()<boost::_mfi::mf1<void, gazebo::common::ModelDatabase, bool>, boost::_bi::list0> (this=0x1030e68,
f=..., a=...) at /usr/include/boost/bind/bind.hpp:313
#5 0x00007f8b7510aff9 in boost::_bi::bind_t<void, boost::_mfi::mf1<void, gazebo::common::ModelDatabase, bool>, boost::_bi::list2<boost::_bi::value<gazebo::common::ModelDatabase*>, boost::_bi::value<bool> > >::operator() (
this=0x1030e58) at /usr/include/boost/bind/bind_template.hpp:20
#6 0x00007f8b7510a00e in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf1<void, gazebo::common::ModelDatabase, bool>, boost::_bi::list2<boost::_bi::value<gazebo::common::ModelDatabase*>, boost::_bi::value<bool> > > >::run (this=0x1030cd0) at /usr/include/boost/thread/detail/thread.hpp:61
#7 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#8 0x00007f8b7371ae9a in start_thread (arg=0x7f8b5fe11700) at pthread_create.c:308
#9 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#10 0x0000000000000000 in ?? ()
Thread 18 (Thread 0x7f8b5c924700 (LWP 9860)):
#0 0x00007f8b71f35363 in epoll_wait () at ../sysdeps/unix/syscall-template.S:82
#1 0x00007f8b746db031 in boost::asio::detail::epoll_reactor::run (this=0x10796c0, block=true, ops=...) at /usr/include/boost/asio/detail/impl/epoll_reactor.ipp:240
#2 0x00007f8b746db7e0 in boost::asio::detail::task_io_service::do_one (this=0x109ab70, lock=..., this_idle_thread=0x7f8b5c923bf0) at /usr/include/boost/asio/detail/impl/task_io_service.ipp:264
#3 0x00007f8b746db580 in boost::asio::detail::task_io_service::run (this=0x109ab70, ec=...) at /usr/include/boost/asio/detail/impl/task_io_service.ipp:130
#4 0x00007f8b746db943 in boost::asio::io_service::run (this=0x1293070) at /usr/include/boost/asio/impl/io_service.ipp:57
#5 0x00007f8b746dc502 in boost::_mfi::mf0<unsigned long, boost::asio::io_service>::operator() (this=0x12522e8, p=0x1293070) at /usr/include/boost/bind/mem_fn_template.hpp:49
#6 0x00007f8b746dc473 in boost::_bi::list1<boost::_bi::value<boost::asio::io_service*> >::operator()<unsigned long, boost::_mfi::mf0<unsigned long, boost::asio::io_service>, boost::_bi::list0> (this=0x12522f8, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:243
#7 0x00007f8b746dc421 in boost::_bi::bind_t<unsigned long, boost::_mfi::mf0<unsigned long, boost::asio::io_service>, boost::_bi::list1<boost::_bi::value<boost::asio::io_service*> > >::operator() (this=0x12522e8)
at /usr/include/boost/bind/bind_template.hpp:20
#8 0x00007f8b746dc3e6 in boost::detail::thread_data<boost::_bi::bind_t<unsigned long, boost::_mfi::mf0<unsigned long, boost::asio::io_service>, boost::_bi::list1<boost::_bi::value<boost::asio::io_service*> > > >::run (
this=0x1252160) at /usr/include/boost/thread/detail/thread.hpp:61
#9 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#10 0x00007f8b7371ae9a in start_thread (arg=0x7f8b5c924700) at pthread_create.c:308
#11 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#12 0x0000000000000000 in ?? ()
Thread 17 (Thread 0x7f8b57fff700 (LWP 9861)):
#0 0x00007f8b7372252d in nanosleep () at ../sysdeps/unix/syscall-template.S:82
#1 0x00007f8b751219f6 in gazebo::common::Time::Sleep (_time=...) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/Time.cc:171
#2 0x00007f8b75121c01 in gazebo::common::Time::MSleep (_ms=10) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/Time.cc:189
#3 0x000000000048bc1d in gazebo::Master::Run (this=0x10a8980) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/Master.cc:299
#4 0x0000000000499c04 in boost::_mfi::mf0<void, gazebo::Master>::operator() (this=0x1168ed8, p=0x10a8980) at /usr/include/boost/bind/mem_fn_template.hpp:49
#5 0x0000000000499b74 in boost::_bi::list1<boost::_bi::value<gazebo::Master*> >::operator()<boost::_mfi::mf0<void, gazebo::Master>, boost::_bi::list0> (this=0x1168ee8, f=..., a=...) at /usr/include/boost/bind/bind.hpp:253
#6 0x0000000000499b23 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::Master>, boost::_bi::list1<boost::_bi::value<gazebo::Master*> > >::operator() (this=0x1168ed8) at /usr/include/boost/bind/bind_template.hpp:20
#7 0x0000000000499ab6 in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::Master>, boost::_bi::list1<boost::_bi::value<gazebo::Master*> > > >::run (this=0x1168d50)
at /usr/include/boost/thread/detail/thread.hpp:61
#8 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#9 0x00007f8b7371ae9a in start_thread (arg=0x7f8b57fff700) at pthread_create.c:308
#10 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#11 0x0000000000000000 in ?? ()
Thread 16 (Thread 0x7f8b575f1700 (LWP 9864)):
#0 0x00007f8b71f29313 in __GI___poll (fds=<optimized out>, nfds=<optimized out>, timeout=<optimized out>) at ../sysdeps/unix/sysv/linux/poll.c:87
#1 0x00007f8b5d1f7876 in ros::poll_sockets(pollfd*, unsigned long, int) () from /opt/ros/hydro/lib/libroscpp.so
#2 0x00007f8b5d268bca in ros::PollSet::update(int) () from /opt/ros/hydro/lib/libroscpp.so
#3 0x00007f8b5d206004 in ros::PollManager::threadFunc() () from /opt/ros/hydro/lib/libroscpp.so
#4 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#5 0x00007f8b7371ae9a in start_thread (arg=0x7f8b575f1700) at pthread_create.c:308
#6 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#7 0x0000000000000000 in ?? ()
Thread 15 (Thread 0x7f8b56df0700 (LWP 9865)):
#0 0x00007f8b71f2e033 in select () at ../sysdeps/unix/syscall-template.S:82
#1 0x00007f8b5cb442b6 in XmlRpc::XmlRpcDispatch::work(double) () from /opt/ros/hydro/lib/libxmlrpcpp.so
#2 0x00007f8b5d1ebd37 in ros::XMLRPCManager::serverThreadFunc() () from /opt/ros/hydro/lib/libroscpp.so
#3 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#4 0x00007f8b7371ae9a in start_thread (arg=0x7f8b56df0700) at pthread_create.c:308
#5 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#6 0x0000000000000000 in ?? ()
Thread 14 (Thread 0x7f8b565ef700 (LWP 9866)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b5d242852 in ros::ROSOutAppender::logThread() () from /opt/ros/hydro/lib/libroscpp.so
#2 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#3 0x00007f8b7371ae9a in start_thread (arg=0x7f8b565ef700) at pthread_create.c:308
#4 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#5 0x0000000000000000 in ?? ()
Thread 13 (Thread 0x7f8b55dee700 (LWP 9873)):
#0 pthread_cond_timedwait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_timedwait.S:215
#1 0x00007f8b5d215b4b in bool boost::condition_variable::timed_wait<boost::date_time::subsecond_duration<boost::posix_time::time_duration, 1000000l> >(boost::unique_lock<boost::mutex>&, boost::date_time::subsecond_duration<boost::posix_time::time_duration, 1000000l> const&) () from /opt/ros/hydro/lib/libroscpp.so
#2 0x00007f8b5d2134f9 in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/hydro/lib/libroscpp.so
#3 0x00007f8b5d24769e in ros::internalCallbackQueueThreadFunc() () from /opt/ros/hydro/lib/libroscpp.so
#4 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#5 0x00007f8b7371ae9a in start_thread (arg=0x7f8b55dee700) at pthread_create.c:308
#6 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#7 0x0000000000000000 in ?? ()
Thread 10 (Thread 0x7f8b3bfff700 (LWP 9876)):
#0 0x00007f8b71e77425 in __GI_raise (sig=<optimized out>) at ../nptl/sysdeps/unix/sysv/linux/raise.c:64
#1 0x00007f8b71e7ab8b in __GI_abort () at abort.c:91
#2 0x00007f8b724cd69d in __gnu_cxx::__verbose_terminate_handler() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#3 0x00007f8b724cb846 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#4 0x00007f8b724cb873 in std::terminate() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#5 0x00007f8b724cb96e in __cxa_throw () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#6 0x0000000000475c9a in boost::throw_exception<boost::lock_error> (e=...) at /usr/include/boost/throw_exception.hpp:61
#7 0x00007f8b5d213538 in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/hydro/lib/libroscpp.so
#8 0x00007f8b5d680e33 in gazebo::GazeboRosApiPlugin::gazeboQueueThread (this=0x10caac0) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_ros/src/gazebo_ros_api_plugin.cpp:205
#9 0x00007f8b5d6f4c80 in boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>::operator() (this=0x12e2ed8, p=0x10caac0) at /usr/include/boost/bind/mem_fn_template.hpp:49
#10 0x00007f8b5d6f2708 in boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> >::operator()<boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list0> (this=0x12e2ee8, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#11 0x00007f8b5d6e7d89 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> > >::operator() (this=0x12e2ed8)
at /usr/include/boost/bind/bind_template.hpp:20
#12 0x00007f8b5d70e3ba in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> > > >::run (this=0x12e2d50)
at /usr/include/boost/thread/detail/thread.hpp:61
#13 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#14 0x00007f8b7371ae9a in start_thread (arg=0x7f8b3bfff700) at pthread_create.c:308
#15 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#16 0x0000000000000000 in ?? ()
Thread 9 (Thread 0x7f8b39467700 (LWP 9880)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b6b0893b3 in void boost::condition_variable_any::wait<boost::unique_lock<boost::recursive_mutex> >(boost::unique_lock<boost::recursive_mutex>&) () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.7.4
#2 0x00007f8b6b08713f in Ogre::DefaultWorkQueue::waitForNextRequest() () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.7.4
#3 0x00007f8b6b08847c in Ogre::DefaultWorkQueue::_threadMain() () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.7.4
#4 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#5 0x00007f8b7371ae9a in start_thread (arg=0x7f8b39467700) at pthread_create.c:308
#6 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#7 0x0000000000000000 in ?? ()
Thread 8 (Thread 0x7f8b38c66700 (LWP 9881)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b6b0893b3 in void boost::condition_variable_any::wait<boost::unique_lock<boost::recursive_mutex> >(boost::unique_lock<boost::recursive_mutex>&) () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.7.4
#2 0x00007f8b6b08713f in Ogre::DefaultWorkQueue::waitForNextRequest() () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.7.4
#3 0x00007f8b6b08847c in Ogre::DefaultWorkQueue::_threadMain() () from /usr/lib/x86_64-linux-gnu/libOgreMain.so.1.7.4
#4 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#5 0x00007f8b7371ae9a in start_thread (arg=0x7f8b38c66700) at pthread_create.c:308
#6 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#7 0x0000000000000000 in ?? ()
Thread 6 (Thread 0x7f8b1f7fe700 (LWP 9915)):
#0 0x00007f8b71f0b277 in sched_yield () at ../sysdeps/unix/syscall-template.S:82
#1 0x00007f8b732149d5 in ?? () from /usr/lib/libtbb.so.2
#2 0x00007f8b73215221 in ?? () from /usr/lib/libtbb.so.2
#3 0x00007f8b7321109d in ?? () from /usr/lib/libtbb.so.2
#4 0x00007f8b7321054b in ?? () from /usr/lib/libtbb.so.2
#5 0x00007f8b7320e08f in ?? () from /usr/lib/libtbb.so.2
#6 0x00007f8b7320e2c9 in ?? () from /usr/lib/libtbb.so.2
#7 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1f7fe700) at pthread_create.c:308
#8 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#9 0x0000000000000000 in ?? ()
Thread 5 (Thread 0x7f8b1f0fd700 (LWP 9918)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b750fbf1c in boost::condition_variable::wait (this=0x18b0f20, m=...) at /usr/include/boost/thread/pthread/condition_variable.hpp:53
#2 0x00007f8b73e4eeb0 in gazebo::sensors::SensorManager::SensorContainer::RunLoop (this=0x18b0e80) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/sensors/SensorManager.cc:463
#3 0x00007f8b73e55d2e in boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>::operator() (this=0x18b6588, p=0x18b0e80) at /usr/include/boost/bind/mem_fn_template.hpp:49
#4 0x00007f8b73e55c9e in boost::_bi::list1<boost::_bi::value<gazebo::sensors::SensorManager::SensorContainer*> >::operator()<boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>, boost::_bi::list0> (
this=0x18b6598, f=..., a=...) at /usr/include/boost/bind/bind.hpp:253
#5 0x00007f8b73e55c4d in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>, boost::_bi::list1<boost::_bi::value<gazebo::sensors::SensorManager::SensorContainer*> > >::operator() (
this=0x18b6588) at /usr/include/boost/bind/bind_template.hpp:20
#6 0x00007f8b73e55c12 in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>, boost::_bi::list1<boost::_bi::value<gazebo::sensors::SensorManager::SensorContainer*> > > >::run (this=0x18b6400) at /usr/include/boost/thread/detail/thread.hpp:61
#7 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#8 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1f0fd700) at pthread_create.c:308
#9 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#10 0x0000000000000000 in ?? ()
Thread 4 (Thread 0x7f8b1e8fc700 (LWP 9919)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b750fbf1c in boost::condition_variable::wait (this=0x18c7100, m=...) at /usr/include/boost/thread/pthread/condition_variable.hpp:53
#2 0x00007f8b73e4eeb0 in gazebo::sensors::SensorManager::SensorContainer::RunLoop (this=0x18c7060) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/sensors/SensorManager.cc:463
#3 0x00007f8b73e55d2e in boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>::operator() (this=0x185d368, p=0x18c7060) at /usr/include/boost/bind/mem_fn_template.hpp:49
#4 0x00007f8b73e55c9e in boost::_bi::list1<boost::_bi::value<gazebo::sensors::SensorManager::SensorContainer*> >::operator()<boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>, boost::_bi::list0> (
this=0x185d378, f=..., a=...) at /usr/include/boost/bind/bind.hpp:253
#5 0x00007f8b73e55c4d in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>, boost::_bi::list1<boost::_bi::value<gazebo::sensors::SensorManager::SensorContainer*> > >::operator() (
this=0x185d368) at /usr/include/boost/bind/bind_template.hpp:20
#6 0x00007f8b73e55c12 in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::sensors::SensorManager::SensorContainer>, boost::_bi::list1<boost::_bi::value<gazebo::sensors::SensorManager::SensorContainer*> > > >::run (this=0x185d1e0) at /usr/include/boost/thread/detail/thread.hpp:61
#7 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#8 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1e8fc700) at pthread_create.c:308
#9 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#10 0x0000000000000000 in ?? ()
Thread 3 (Thread 0x7f8b1e0fb700 (LWP 9920)):
#0 gazebo::math::equal<double> (_a=@0x3dbafd8: 0.040749117732048035, _b=@0x7f8b1e0f93d8: -0.45306369662284851, _epsilon=@0x7f8b1e0f9338: 0.001) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/math/Helpers.hh:137
#1 0x00007f8b72fe2c13 in gazebo::math::Vector3::operator== (this=0x3dbafd0, _pt=...) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/math/Vector3.cc:320
#2 0x00007f8b750e8c1d in gazebo::common::SubMesh::RecalculateNormals (this=0x3d586a0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/Mesh.cc:788
#3 0x00007f8b750e63f5 in gazebo::common::Mesh::RecalculateNormals (this=0x3d604a0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/Mesh.cc:321
#4 0x00007f8b750f0e2b in gazebo::common::MeshManager::CreateSphere (this=0x7f8b745a96a0, name=..., radius=0.5, rings=32, segments=32) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/MeshManager.cc:286
#5 0x00007f8b750eed15 in gazebo::common::MeshManager::MeshManager (this=0x7f8b745a96a0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/MeshManager.cc:53
#6 0x00007f8b7422cf17 in SingletonT<gazebo::common::MeshManager>::GetInstance () at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/SingletonT.hh:48
#7 0x00007f8b7422a4a7 in SingletonT<gazebo::common::MeshManager>::Instance () at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/common/SingletonT.hh:36
#8 0x00007f8b742df325 in gazebo::physics::TrimeshShape::Init (this=0x1991230) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/TrimeshShape.cc:55
#9 0x00007f8b6fe7478a in gazebo::physics::ODETrimeshShape::Init (this=0x1991230) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/ode/ODETrimeshShape.cc:100
#10 0x00007f8b742487a6 in gazebo::physics::Collision::Init (this=0x18b4700) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/Collision.cc:118
#11 0x00007f8b7429cdba in gazebo::physics::Link::Init (this=0x19fdec0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/Link.cc:246
#12 0x00007f8b6fe58129 in gazebo::physics::ODELink::Init (this=0x19fdec0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/ode/ODELink.cc:96
#13 0x00007f8b742b5a65 in gazebo::physics::Model::Init (this=0x1cf3960) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/Model.cc:183
#14 0x00007f8b742ee01b in gazebo::physics::World::ProcessFactoryMsgs (this=0x11379c0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/World.cc:1601
#15 0x00007f8b742efea0 in gazebo::physics::World::ProcessMessages (this=0x11379c0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/World.cc:1817
#16 0x00007f8b742e6c97 in gazebo::physics::World::Step (this=0x11379c0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/World.cc:528
#17 0x00007f8b742e5a4e in gazebo::physics::World::RunLoop (this=0x11379c0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/World.cc:365
#18 0x00007f8b74306506 in boost::_mfi::mf0<void, gazebo::physics::World>::operator() (this=0x18d7538, p=0x11379c0) at /usr/include/boost/bind/mem_fn_template.hpp:49
#19 0x00007f8b74305580 in boost::_bi::list1<boost::_bi::value<gazebo::physics::World*> >::operator()<boost::_mfi::mf0<void, gazebo::physics::World>, boost::_bi::list0> (this=0x18d7548, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#20 0x00007f8b74304515 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::physics::World>, boost::_bi::list1<boost::_bi::value<gazebo::physics::World*> > >::operator() (this=0x18d7538)
at /usr/include/boost/bind/bind_template.hpp:20
#21 0x00007f8b74308084 in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::physics::World>, boost::_bi::list1<boost::_bi::value<gazebo::physics::World*> > > >::run (this=0x18d73b0)
at /usr/include/boost/thread/detail/thread.hpp:61
#22 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#23 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1e0fb700) at pthread_create.c:308
#24 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#25 0x0000000000000000 in ?? ()
Thread 2 (Thread 0x7f8b1d8fa700 (LWP 9921)):
#0 pthread_cond_wait@@GLIBC_2.3.2 () at ../nptl/sysdeps/unix/sysv/linux/x86_64/pthread_cond_wait.S:162
#1 0x00007f8b750fbf1c in boost::condition_variable::wait (this=0x1138110, m=...) at /usr/include/boost/thread/pthread/condition_variable.hpp:53
#2 0x00007f8b742f05a0 in gazebo::physics::World::LogWorker (this=0x11379c0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/physics/World.cc:1889
#3 0x00007f8b74306506 in boost::_mfi::mf0<void, gazebo::physics::World>::operator() (this=0x18388a8, p=0x11379c0) at /usr/include/boost/bind/mem_fn_template.hpp:49
#4 0x00007f8b74305580 in boost::_bi::list1<boost::_bi::value<gazebo::physics::World*> >::operator()<boost::_mfi::mf0<void, gazebo::physics::World>, boost::_bi::list0> (this=0x18388b8, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#5 0x00007f8b74304515 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::physics::World>, boost::_bi::list1<boost::_bi::value<gazebo::physics::World*> > >::operator() (this=0x18388a8)
at /usr/include/boost/bind/bind_template.hpp:20
#6 0x00007f8b74308084 in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::physics::World>, boost::_bi::list1<boost::_bi::value<gazebo::physics::World*> > > >::run (this=0x1838720)
at /usr/include/boost/thread/detail/thread.hpp:61
#7 0x00007f8b72b8bce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#8 0x00007f8b7371ae9a in start_thread (arg=0x7f8b1d8fa700) at pthread_create.c:308
#9 0x00007f8b71f34ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#10 0x0000000000000000 in ?? ()
Thread 1 (Thread 0x7f8b75541840 (LWP 9844)):
#0 0x00007f8b724b6007 in std::string::assign(std::string const&) () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#1 0x00007f8b746f36fc in gazebo::transport::TopicManager::Unadvertise (this=0x6c13e0, _topic=...) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/transport/TopicManager.cc:387
#2 0x00007f8b746f1fa0 in gazebo::transport::TopicManager::Fini (this=0x6c13e0) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/transport/TopicManager.cc:83
#3 0x00007f8b746fab36 in gazebo::transport::fini () at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/transport/Transport.cc:144
#4 0x000000000049a08a in gazebo::fini () at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/gazebo.cc:108
#5 0x0000000000471373 in gazebo::Server::Fini (this=0x1058380) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/Server.cc:422
#6 0x000000000046b9e5 in main (argc=8, argv=0x7fffdf7ea608) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/server_main.cc:52
From time to time I also get another error, but in thread 1. I assume in that case the callback queue mutex was still locked in thread 10 when thread 1 tries to delete the object:
gzserver: /usr/include/boost/thread/pthread/condition_variable_fwd.hpp:46: boost::condition_variable::~condition_variable(): Assertion `!pthread_mutex_destroy(&internal_mutex)' failed.
Here is the corresponding stack trace (only thread 1 and 10):
Thread 10 (Thread 0x7f17ca7fc700 (LWP 9474)):
#0 0x00007f17e35ee510 in pthread_mutex_lock@plt () from /opt/ros/hydro/lib/libroscpp.so
#1 0x00007f17e363c1b7 in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/hydro/lib/libroscpp.so
#2 0x00007f17e3aa9e33 in gazebo::GazeboRosApiPlugin::gazeboQueueThread (this=0x2428c30) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_ros/src/gazebo_ros_api_plugin.cpp:205
#3 0x00007f17e3b1dc80 in boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>::operator() (this=0x24e5a68, p=0x2428c30) at /usr/include/boost/bind/mem_fn_template.hpp:49
#4 0x00007f17e3b1b708 in boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> >::operator()<boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list0> (this=0x24e5a78, f=..., a=...)
at /usr/include/boost/bind/bind.hpp:253
#5 0x00007f17e3b10d89 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> > >::operator() (this=0x24e5a68)
at /usr/include/boost/bind/bind_template.hpp:20
#6 0x00007f17e3b373ba in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, gazebo::GazeboRosApiPlugin>, boost::_bi::list1<boost::_bi::value<gazebo::GazeboRosApiPlugin*> > > >::run (this=0x24e58e0)
at /usr/include/boost/thread/detail/thread.hpp:61
#7 0x00007f17fcfdcce9 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#8 0x00007f17fdb6be9a in start_thread (arg=0x7f17ca7fc700) at pthread_create.c:308
#9 0x00007f17fc385ccd in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:112
#10 0x0000000000000000 in ?? ()
Thread 1 (Thread 0x7f17ff992840 (LWP 9436)):
#0 0x00007f17fc2c8425 in __GI_raise (sig=<optimized out>) at ../nptl/sysdeps/unix/sysv/linux/raise.c:64
#1 0x00007f17fc2cbb8b in __GI_abort () at abort.c:91
#2 0x00007f17fc2c10ee in __assert_fail_base (fmt=<optimized out>, assertion=0x7f17e3697ea8 "!pthread_mutex_destroy(&internal_mutex)", file=0x7f17e3697e68 "/usr/include/boost/thread/pthread/condition_variable_fwd.hpp",
line=<optimized out>, function=<optimized out>) at assert.c:94
#3 0x00007f17fc2c1192 in __GI___assert_fail (assertion=0x7f17e3697ea8 "!pthread_mutex_destroy(&internal_mutex)", file=0x7f17e3697e68 "/usr/include/boost/thread/pthread/condition_variable_fwd.hpp", line=46,
function=0x7f17e369ce20 "boost::condition_variable::~condition_variable()") at assert.c:103
#4 0x00007f17e363a0a6 in ros::CallbackQueue::~CallbackQueue() () from /opt/ros/hydro/lib/libroscpp.so
#5 0x00007f17e3aa7933 in gazebo::GazeboRosApiPlugin::~GazeboRosApiPlugin (this=0x2428c30, __in_chrg=<optimized out>) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_ros/src/gazebo_ros_api_plugin.cpp:38
#6 0x00007f17e3aa85a8 in gazebo::GazeboRosApiPlugin::~GazeboRosApiPlugin (this=0x2428c30, __in_chrg=<optimized out>) at /home/meyer/ros/hydro/gazebo/src/gazebo_ros_pkgs/gazebo_ros/src/gazebo_ros_api_plugin.cpp:98
#7 0x000000000049caa2 in boost::checked_delete<gazebo::SystemPlugin> (x=0x2428c30) at /usr/include/boost/checked_delete.hpp:34
#8 0x000000000049cd72 in boost::detail::sp_counted_impl_p<gazebo::SystemPlugin>::dispose (this=0x2300960) at /usr/include/boost/smart_ptr/detail/sp_counted_impl.hpp:78
#9 0x000000000046c6f0 in boost::detail::sp_counted_base::release (this=0x2300960) at /usr/include/boost/smart_ptr/detail/sp_counted_base_gcc_x86.hpp:145
#10 0x000000000046c769 in boost::detail::shared_count::~shared_count (this=0x226c398, __in_chrg=<optimized out>) at /usr/include/boost/smart_ptr/detail/shared_count.hpp:217
#11 0x000000000049b18c in boost::shared_ptr<gazebo::SystemPlugin>::~shared_ptr (this=0x226c390, __in_chrg=<optimized out>) at /usr/include/boost/smart_ptr/shared_ptr.hpp:168
#12 0x000000000049ccb2 in std::_Destroy<boost::shared_ptr<gazebo::SystemPlugin> > (__pointer=0x226c390) at /usr/include/c++/4.6/bits/stl_construct.h:94
#13 0x000000000049cb73 in std::_Destroy_aux<false>::__destroy<boost::shared_ptr<gazebo::SystemPlugin>*> (__first=0x226c390, __last=0x226c3a0) at /usr/include/c++/4.6/bits/stl_construct.h:104
#14 0x000000000049ca0a in std::_Destroy<boost::shared_ptr<gazebo::SystemPlugin>*> (__first=0x226c380, __last=0x226c3a0) at /usr/include/c++/4.6/bits/stl_construct.h:127
#15 0x000000000049c68b in std::_Destroy<boost::shared_ptr<gazebo::SystemPlugin>*, boost::shared_ptr<gazebo::SystemPlugin> > (__first=0x226c380, __last=0x226c3a0) at /usr/include/c++/4.6/bits/stl_construct.h:153
#16 0x000000000049bfb6 in std::vector<boost::shared_ptr<gazebo::SystemPlugin>, std::allocator<boost::shared_ptr<gazebo::SystemPlugin> > >::_M_erase_at_end (this=0x6c19b0, __pos=0x226c380)
at /usr/include/c++/4.6/bits/stl_vector.h:1255
#17 0x000000000049b9ca in std::vector<boost::shared_ptr<gazebo::SystemPlugin>, std::allocator<boost::shared_ptr<gazebo::SystemPlugin> > >::clear (this=0x6c19b0) at /usr/include/c++/4.6/bits/stl_vector.h:1040
#18 0x000000000049a085 in gazebo::fini () at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/gazebo.cc:107
#19 0x0000000000471373 in gazebo::Server::Fini (this=0x226a380) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/Server.cc:422
#20 0x000000000046b9e5 in main (argc=8, argv=0x7fff172d29d8) at /home/meyer/ros/hydro/gazebo/gazebo/gazebo/server_main.cc:52
Asked by Johannes Meyer on 2013-07-03 07:11:41 UTC
Answers
Ticketed and (hopefully) fixed in ros-simulation/gazebo_ros_pkgs#65.
Asked by Johannes Meyer on 2013-07-16 14:35:20 UTC
Comments
Could you post the backtrace output from all the threads: (gdb) thread apply all bt. The performance of gazebo 1.8.6 is greatly improved. Depending on the world and sensors, it'll run near or faster than real-time.
Asked by nkoenig on 2013-07-03 14:09:45 UTC
Unfortunately I cannot reproduce the error at the moment because of issue 748. But I found out that the error is caused by a gzthrow in the Camera.cc file as min_angle > max_angle in my config. I copied this over from the normal ray sensor we used in Gazebo 1.5 and it worked fine there. The error message is never printed and the lock error occurs if the server calls the plugins' deconstructors afterwards while the gazeboQueueThread is still running.
Asked by Johannes Meyer on 2013-07-04 05:09:21 UTC