We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
__none
Terminal 1:
$ rosparam get /use_sim_time false $ rosrun topic_tools demux in out1 out2 [ INFO] [1582155387.681282669] [ros.topic_tools]: PRE added out1 to demux [ INFO] [1582155387.682005489] [ros.topic_tools]: PRE added out2 to demux [ INFO] [1582155391.401237849] [ros.topic_tools]: Added publisher /out1 to demux! [ INFO] [1582155391.402408733] [ros.topic_tools]: Added publisher /out2 to demux! [ INFO] [1582155391.402457438] [ros.topic_tools]: Sleeping 0.5 sec. [ INFO] [1582155395.597647678] [ros.topic_tools]: demux selected to no output. Illegal memory access (SIGSEGV) (core dumped [dump saved])
Terminal 2:
$ rosservice call /demux/select "topic: '__none'" prev_topic: "/out1" $ rostopic pub -1 in std_msgs/Bool "data: false" publishing and latching message for 3.0 seconds $ rosservice call /demux/select "topic: 'out1'" ERROR: Unable to communicate with service [/demux/select], address [rosrpc://cras-11:35591]
At first, I thought it's the same as #1366, but in the end it looks like a different issue.
Here's the core file for the demux node: core.zip
And this is the stack trace:
#0 __GI___pthread_mutex_lock (mutex=0x110) at ../nptl/pthread_mutex_lock.c:65 #1 0x00007f7f42e563d0 in boost::posix::pthread_mutex_lock (m=<optimized out>) at /usr/include/boost/thread/pthread/mutex.hpp:62 #2 boost::mutex::lock (this=<optimized out>) at /usr/include/boost/thread/pthread/mutex.hpp:116 #3 boost::unique_lock<boost::mutex>::lock (this=<synthetic pointer>) at /usr/include/boost/thread/lock_types.hpp:346 #4 boost::unique_lock<boost::mutex>::unique_lock (m_=..., this=<synthetic pointer>) at /usr/include/boost/thread/lock_types.hpp:124 #5 ros::Publication::hasSubscribers (this=0x0) at ./src/libros/publication.cpp:399 #6 0x00007f7f42e47246 in ros::TopicManager::publish(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::function<ros::SerializedMessage ()> const&, ros::SerializedMessage&) (this=0x55699fd528c0, topic=<error: Cannot access memory at address 0x53726574006e692f>, serfunc=..., m=...) at ./src/libros/topic_manager.cpp:713 #7 0x000055699e27f047 in ros::Publisher::publish<topic_tools::ShapeShifter const> (message=..., this=0x55699fd5a010) at /opt/ros/melodic/include/ros/publisher.h:88 #8 in_cb (msg=...) at ./src/demux.cpp:159 #9 0x000055699e287c8e in boost::function1<void, boost::shared_ptr<topic_tools::ShapeShifter const> const&>::operator() (a0=..., this=<optimized out>) at /usr/include/boost/function/function_template.hpp:759 #10 boost::detail::function::void_function_obj_invoker1<boost::function<void (boost::shared_ptr<topic_tools::ShapeShifter const> const&)>, void, boost::shared_ptr<topic_tools::ShapeShifter const> >::invoke(boost::detail::function::function_buffer&, boost::shared_ptr<topic_tools::ShapeShifter const>) (function_obj_ptr=..., a0=...) at /usr/include/boost/function/function_template.hpp:159 #11 0x000055699e28a06d in boost::function1<void, boost::shared_ptr<topic_tools::ShapeShifter const> >::operator() (a0=..., this=0x55699fd57ae8) at /usr/include/boost/function/function_template.hpp:759 #12 ros::SubscriptionCallbackHelperT<boost::shared_ptr<topic_tools::ShapeShifter const> const&, void>::call (this=0x55699fd57ae0, params=...) at /opt/ros/melodic/include/ros/subscription_callback_helper.h:144 #13 0x00007f7f42eba792 in ros::SubscriptionQueue::call (this=0x55699fd51d80) at ./src/libros/subscription_queue.cpp:164 #14 0x00007f7f42e64e8c in ros::CallbackQueue::callOneCB (this=this@entry=0x55699fd505a0, tls=tls@entry=0x55699fd57ea0) at ./src/libros/callback_queue.cpp:406 #15 0x00007f7f42e6627b in ros::CallbackQueue::callAvailable (this=this@entry=0x55699fd505a0, timeout=...) at ./src/libros/callback_queue.cpp:347 #16 0x00007f7f42ebe2e9 in ros::SingleThreadedSpinner::spin (this=<optimized out>, queue=0x55699fd505a0) at ./src/libros/spinner.cpp:141 #17 0x00007f7f42ea6b5b in ros::spin () at ./src/libros/init.cpp:547 #18 0x000055699e27d8d2 in main (argc=<optimized out>, argv=<optimized out>) at ./src/demux.cpp:298
The text was updated successfully, but these errors were encountered:
If I don't publish between selecting __none and another topic, the crash doesn't occur.
Sorry, something went wrong.
No branches or pull requests
Terminal 1:
Terminal 2:
At first, I thought it's the same as #1366, but in the end it looks like a different issue.
Here's the core file for the demux node: core.zip
And this is the stack trace:
The text was updated successfully, but these errors were encountered: