Open YannickRiou opened 3 years ago
Are you recreating the task or reusing it? In this example, we are reusing a task several times without any issues.
Also, it would be helpful to know, which variable is causing the segfault. Looks like the topics created by introspection are broken here. Could you try to run with AddressSanitizer, i.e. prepending LD_PRELOAD=libasan.so
?
We are re-creating the task with this as the parameter or content of the task can be different :
std::unique_ptr<Task> lastPlannedTask_;
lastPlannedTask_ = std::make_unique<Task>(taskName);
So it's not the same use as the example you provided where the content of the task (stages) stays the same.
I never used Asan, but will give it a try and get back with the result.
I never used Asan, but will give it a try and get back with the result.
I'm curious about the result.
You could try to reset and re-create the task in two steps. I remember we have used that scheme in the past:
lastPlannedTask_.reset();
lastPlannedTask_ = std::make_unique<Task>(taskName);
This way, the task is first reset before a new one is created.
std::uniqueptr
lastPlannedTask ; lastPlannedTask_ = std::make_unique(taskName);
If taskName
is the same between instantiations, make sure you actually use lastPlannedTask_.reset()
before creating the new task.
Otherwise you at least get problems with the introspection ROS service, though (in theory) the publishers should not be affected.
If
taskName
is the same between instantiations [...]
I thought that was the problem so I tried adding a random number after the task name to be sure that every task has a unique name and I also ran into the segfault.
You could try to reset and re-create the task in two steps.
It seems to resolve the problem. After running the same pick/place task around 30 times, the segfault error doesn't occur anymore.
About the Asan result, here it is, but in my opinion, it doesn't give no new information :
ASAN:SIGSEGV
=================================================================
==31252==ERROR: AddressSanitizer: SEGV on unknown address 0x000000000120 (pc 0x7f02ffb5bd44 bp 0x000000000000 sp 0x7f02e60e8920 T8)
#0 0x7f02ffb5bd43 in pthread_mutex_lock (/lib/x86_64-linux-gnu/libpthread.so.0+0x9d43)
#1 0x7f0300ae821f in ros::Publication::hasSubscribers() (/opt/ros/kinetic/lib/libroscpp.so+0xd521f)
#2 0x7f0300ad9a1d in ros::TopicManager::publish(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::function<ros::SerializedMessage ()> const&, ros::SerializedMessage&) (/opt/ros/kinetic/lib/libroscpp.so+0xc6a1d)
#3 0x7f030278c15b in void ros::Publisher::publish<moveit_task_constructor_msgs::TaskDescription_<std::allocator<void> > >(moveit_task_constructor_msgs::TaskDescription_<std::allocator<void> > const&) const (/home/yriou/PR2/director_task/ws_ros_pkg_old/devel/.private/moveit_task_constructor_core/lib/libmoveit_task_constructor_core.so+0x22615b)
#4 0x7f0302787687 in moveit::task_constructor::Introspection::publishTaskDescription() (/home/yriou/PR2/director_task/ws_ros_pkg_old/devel/.private/moveit_task_constructor_core/lib/libmoveit_task_constructor_core.so+0x221687)
#5 0x7f03027e4efd in moveit::task_constructor::Task::init() (/home/yriou/PR2/director_task/ws_ros_pkg_old/devel/.private/moveit_task_constructor_core/lib/libmoveit_task_constructor_core.so+0x27eefd)
#6 0x7f03027e4ff8 in moveit::task_constructor::Task::plan(unsigned long) (/home/yriou/PR2/director_task/ws_ros_pkg_old/devel/.private/moveit_task_constructor_core/lib/libmoveit_task_constructor_core.so+0x27eff8)
#7 0x60aba6 in motionPlanning::planCallback(boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x60aba6)
#8 0x695708 in boost::_mfi::mf3<void, motionPlanning, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&>::operator()(motionPlanning*, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&) const (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x695708)
#9 0x68749c in void boost::_bi::list4<boost::_bi::value<motionPlanning*>, boost::arg<1>, boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*>, boost::_bi::value<ros::ServiceClient> >::operator()<boost::_mfi::mf3<void, motionPlanning, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&>, boost::_bi::list1<boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&> >(boost::_bi::type<void>, boost::_mfi::mf3<void, motionPlanning, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&>&, boost::_bi::list1<boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&>&, int) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x68749c)
#10 0x6789d0 in void boost::_bi::bind_t<void, boost::_mfi::mf3<void, motionPlanning, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&>, boost::_bi::list4<boost::_bi::value<motionPlanning*>, boost::arg<1>, boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*>, boost::_bi::value<ros::ServiceClient> > >::operator()<boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&>(boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x6789d0)
#11 0x664291 in boost::detail::function::void_function_obj_invoker1<boost::_bi::bind_t<void, boost::_mfi::mf3<void, motionPlanning, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*, ros::ServiceClient&>, boost::_bi::list4<boost::_bi::value<motionPlanning*>, boost::arg<1>, boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*>, boost::_bi::value<ros::ServiceClient> > >, void, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&>::invoke(boost::detail::function::function_buffer&, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x664291)
#12 0x653932 in boost::function1<void, boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&>::operator()(boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&) const (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x653932)
#13 0x642c6b in actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >::executeLoop() (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x642c6b)
#14 0x6ddc68 in boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >::operator()(actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*) const (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x6ddc68)
#15 0x6db7db in void boost::_bi::list1<boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*> >::operator()<boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >, boost::_bi::list0>(boost::_bi::type<void>, boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >&, boost::_bi::list0&, int) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x6db7db)
#16 0x6d58a9 in boost::_bi::bind_t<void, boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >, boost::_bi::list1<boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*> > >::operator()() (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x6d58a9)
#17 0x6d0d83 in boost::detail::thread_data<boost::_bi::bind_t<void, boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >, boost::_bi::list1<boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*> > > >::run() (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x6d0d83)
#18 0x7f02ffd805d4 (/usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0+0x115d4)
#19 0x7f02ffb596b9 in start_thread (/lib/x86_64-linux-gnu/libpthread.so.0+0x76b9)
#20 0x7f02fefee51c in clone (/lib/x86_64-linux-gnu/libc.so.6+0x10751c)
AddressSanitizer can not provide additional info.
SUMMARY: AddressSanitizer: SEGV ??:0 pthread_mutex_lock
Thread T8 created by T0 here:
#0 0x7f0302b4f253 in pthread_create (/usr/lib/x86_64-linux-gnu/libasan.so.2.0.0+0x36253)
#1 0x7f02ffd7f2e8 in boost::thread::start_thread_noexcept() (/usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0+0x102e8)
#2 0x643182 in boost::thread::thread<boost::_bi::bind_t<void, boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >, boost::_bi::list1<boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*> > > >(boost::_bi::bind_t<void, boost::_mfi::mf0<void, actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > > >, boost::_bi::list1<boost::_bi::value<actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >*> > >&&) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x643182)
#3 0x62960f in actionlib::SimpleActionServer<pr2_motion_tasks_msgs::planAction_<std::allocator<void> > >::SimpleActionServer(ros::NodeHandle, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, boost::function<void (boost::shared_ptr<pr2_motion_tasks_msgs::planGoal_<std::allocator<void> > const> const&)>, bool) (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x62960f)
#4 0x60dabc in main (/home/yriou/PR2/director_task/ws_dt/devel/.private/pr2_mtc/lib/pr2_mtc/pr2_tasks+0x60dabc)
#5 0x7f02fef0783f in __libc_start_main (/lib/x86_64-linux-gnu/libc.so.6+0x2083f)
==31252==ABORTING
Also, to understand better, what is the action of the reset method ?
lastPlannedTask_.reset();
just releases and frees the task pointer before creating a new one.
From your 2nd backtrace, I learned that you are creating new tasks on-the-fly within the action server thread. What puzzles me is that the segfault occurs in a very basic function (pthread_mutex_lock
). This hints at some problem in roscpp or at some stack corruption. The latter should have been revealed by asan though.
@YannickRiou: Can we close this issue?
I think so for now, I only had one segfault since I applied the above fix and maybe it wasn't related to this issue.
Sorry, I would like to keep this open as a reminder that we probably want to allow your original code at some point. That requires some refactoring though.
I'm still not sure where the original segfault comes from. To actually reproduce this issue, it would be helpful to have complete, but minimal example code producing the segfault.
ROS Distro : Kinetic Moveit Task constructor version : https://github.com/YannickRiou/moveit_task_constructor
Actual behavior : I have a ros node that create a task, fill it with stages and then plan it. After some runs of creating multiple tasks (one after the another eg. I create a pick task, plan it, execute it, then create a place task, plan it, execute it, etc.), the node throws a segfault with the following backtrace :
Here is how I create my task :
I can run this code several times without having problems, but at some point, the segfault happens.
The problem seems to come from the puslisher of the task description in the plan function according to the backtrace.
Is there a limitation of creating tasks one after another on MTC (topic lifetime, etc.)?
Feel free to ask if something is unclear or missing.