-
Notifications
You must be signed in to change notification settings - Fork 927
Segmentation fault in ros::Subscription::pubUpdate #1079
Description
Hello,
I am having an issue similar to http://answers.ros.org/question/238675/program-received-signal-sigsegv-segmentation-fault-in-rossubscriptionpubupdate/ .
FYI I am on Ubuntu 14.04 with ROS indigo with the Baxter robot. I cannot update since indigo is the latest supported version for the baxter.
I investigated a bit the issue, and here is some gdb output:
(gdb) where
#0 0x00007ffff6e19853 in std::basic_ostream<char, std::char_traits<char> >& std::operator<< <char, std::char_traits<char>, std::allocator<char> >(std::basic_ostream<char, std::char_traits<char> >&, std::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#1 0x00007ffff78034d0 in ros::Subscription::pubUpdate (this=0x98bde0, new_pubs=std::vector of length 3, capacity 4 = {...})
at /home/scazlab/ros_stable_ws/src/ros_comm/roscpp/src/libros/subscription.cpp:230
#2 0x00007ffff777e76c in ros::TopicManager::pubUpdate (this=0x6bedc0, topic="/tf", pubs=std::vector of length 3, capacity 4 = {...})
at /home/scazlab/ros_stable_ws/src/ros_comm/roscpp/src/libros/topic_manager.cpp:583
#3 0x00007ffff77822c8 in ros::TopicManager::pubUpdateCallback (this=0x6bedc0, params=..., result=...) at /home/scazlab/ros_stable_ws/src/ros_comm/roscpp/src/libros/topic_manager.cpp:1019
#4 0x00007ffff7788294 in boost::_mfi::mf2<void, ros::TopicManager, XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&>::operator() (this=0x6bf038, p=0x6bedc0, a1=..., a2=...)
at /usr/include/boost/bind/mem_fn_template.hpp:280
#5 0x00007ffff7787c94 in boost::_bi::list3<boost::_bi::value<ros::TopicManager*>, boost::arg<1>, boost::arg<2> >::operator()<boost::_mfi::mf2<void, ros::TopicManager, XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&>, boost::_bi::list2<XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&> > (this=0x6bf048, f=..., a=...) at /usr/include/boost/bind/bind.hpp:392
#6 0x00007ffff778777a in boost::_bi::bind_t<void, boost::_mfi::mf2<void, ros::TopicManager, XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&>, boost::_bi::list3<boost::_bi::value<ros::TopicManager*>, boost::arg<1>, boost::arg<2> > >::operator()<XmlRpc::XmlRpcValue, XmlRpc::XmlRpcValue> (this=0x6bf038, a1=..., a2=...) at /usr/include/boost/bind/bind_template.hpp:61
#7 0x00007ffff77870aa in boost::detail::function::void_function_obj_invoker2<boost::_bi::bind_t<void, boost::_mfi::mf2<void, ros::TopicManager, XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&>, boost::_bi::list3<boost::_bi::value<ros::TopicManager*>, boost::arg<1>, boost::arg<2> > >, void, XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&>::invoke (function_obj_ptr=..., a0=...,
a1=...) at /usr/include/boost/function/function_template.hpp:153
#8 0x00007ffff7769600 in boost::function2<void, XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&>::operator() (this=0x6bf030, a0=..., a1=...)
at /usr/include/boost/function/function_template.hpp:767
#9 0x00007ffff77693c1 in ros::XMLRPCCallWrapper::execute (this=0x6bf010, params=..., result=...) at /home/scazlab/ros_stable_ws/src/ros_comm/roscpp/src/libros/xmlrpc_manager.cpp:82
#10 0x00007ffff4702314 in XmlRpc::XmlRpcServerConnection::executeMethod (this=0x7fffcc0008c0, methodName="publisherUpdate", params=..., result=...)
at /home/scazlab/ros_stable_ws/src/ros_comm/xmlrpcpp/src/XmlRpcServerConnection.cpp:266
#11 0x00007ffff4701f59 in XmlRpc::XmlRpcServerConnection::executeRequest (this=0x7fffcc0008c0) at /home/scazlab/ros_stable_ws/src/ros_comm/xmlrpcpp/src/XmlRpcServerConnection.cpp:222
#12 0x00007ffff4701d5a in XmlRpc::XmlRpcServerConnection::writeResponse (this=0x7fffcc0008c0) at /home/scazlab/ros_stable_ws/src/ros_comm/xmlrpcpp/src/XmlRpcServerConnection.cpp:185
#13 0x00007ffff470179a in XmlRpc::XmlRpcServerConnection::handleEvent (this=0x7fffcc0008c0) at /home/scazlab/ros_stable_ws/src/ros_comm/xmlrpcpp/src/XmlRpcServerConnection.cpp:66
#14 0x00007ffff46fda96 in XmlRpc::XmlRpcDispatch::work (this=0x6bcb70, timeout=0.10000000000000001) at /home/scazlab/ros_stable_ws/src/ros_comm/xmlrpcpp/src/XmlRpcDispatch.cpp:134
#15 0x00007ffff46ff16a in XmlRpc::XmlRpcServer::work (this=0x6bcb60, msTime=0.10000000000000001) at /home/scazlab/ros_stable_ws/src/ros_comm/xmlrpcpp/src/XmlRpcServer.cpp:133
#16 0x00007ffff776864b in ros::XMLRPCManager::serverThreadFunc (this=0x6bcb40) at /home/scazlab/ros_stable_ws/src/ros_comm/roscpp/src/libros/xmlrpc_manager.cpp:268
#17 0x00007ffff776eb07 in boost::_mfi::mf0<void, ros::XMLRPCManager>::operator() (this=0x6c0f48, p=0x6bcb40) at /usr/include/boost/bind/mem_fn_template.hpp:49
#18 0x00007ffff776ea6a in boost::_bi::list1<boost::_bi::value<ros::XMLRPCManager*> >::operator()<boost::_mfi::mf0<void, ros::XMLRPCManager>, boost::_bi::list0> (this=0x6c0f58, f=...,
a=...) at /usr/include/boost/bind/bind.hpp:253
#19 0x00007ffff776ea19 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, ros::XMLRPCManager>, boost::_bi::list1<boost::_bi::value<ros::XMLRPCManager*> > >::operator() (this=0x6c0f48)
at /usr/include/boost/bind/bind_template.hpp:20
#20 0x00007ffff776e9de in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, ros::XMLRPCManager>, boost::_bi::list1<boost::_bi::value<ros::XMLRPCManager*> > > >::run (this=0x6c0d90) at /usr/include/boost/thread/detail/thread.hpp:117
#21 0x00007ffff3fb7a4a in ?? () from /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.54.0
#22 0x00007ffff3d96184 in start_thread (arg=0x7fffd786c700) at pthread_create.c:312
#23 0x00007ffff68a5bed in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:111
This is part of my bt full:
(gdb) bt full
#0 0x00007ffff6e19853 in std::basic_ostream<char, std::char_traits<char> >& std::operator<< <char, std::char_traits<char>, std::allocator<char> >(std::basic_ostream<char, std::char_traits<char> >&, std::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
No symbol table info available.
#1 0x00007ffff78034d0 in ros::Subscription::pubUpdate (this=0x98bde0, new_pubs=std::vector of length 3, capacity 4 = {...})
at /home/scazlab/ros_stable_ws/src/ros_comm/roscpp/src/libros/subscription.cpp:230
spc = {px = , pn = {pi_ = }}
ss = <incomplete type>
lock = {m = 0x7fffcc004980, is_locked = 48}
it = {px = , pn = {pi_ = }}
end = {px = , pn = {pi_ = }}
retval = true
__PRETTY_FUNCTION__ = "bool ros::Subscription::pubUpdate(const V_string&)"
additions = std::vector of length 91676117, capacity 24169600 = {"", "", "",
"\220\304@", '\000' <repeats 22 times>, "?xml ve\260M\255\367\377\177\000\000\060H\000\314\377\177\000\000\020H\000\314\377\177\000\000མ\000\000\000\000\000\300\275\230\000\000\000\000\000\312\026\000\000m>\r\n8\026\000\314\377\177", '\000' <repeats 26 times>, "`P\000\314\377\177\000\000hP\000\314\377\177\000\000hP\000\314\377\177\000\000alue><va\000\000\000\000<arr\000\000\000\000\000\000\000\000\240H\000\314\377\177\000\000\240H\000\314\377\177", '\000' <repeats 11 times>, "lue>192xA\020\320\377\177\000\000"...,
<error reading variable: Cannot access memory at address 0x38>, <error reading variable: Cannot access memory at address 0x2d>, "",
And the issue is in this file, at line 230, ie when it does ss << (*spc)->getPublisherXMLRPCURI() << ", ";.
If you take a look at the code there you see that publisher_links_ is not protected by its mutex, as in other parts of the codebase (eg line 253 of the same file). Adding a scoped_lock to that line seems to fix the issue to me.
If that sounds fine with you, I can proceed to open a pull request, but I wanted to have your opinion before doing so.
Thanks!