ikd-Tree
ikd-Tree copied to clipboard
Why is there a segmentation fault here?
Stack trace (most recent call last):
#21 Object "/usr/lib/x86_64-linux-gnu/ld-2.31.so", at 0xffffffffffffffff, in
#20 Object "/home/jcwang/code/ws_di-lui-sam/src/di_lui_sam/cmake-build-debug/devel/lib/multi_proxy/multi_proxy_subMapFusion", at 0x555555600ead, in start
#19 Source "../csu/libc-start.c", line 308, in libc_start_main [0x7ffff45e6082]
#18 Source "/home/jcwang/code/ws_di-lui-sam/src/di_lui_sam/src/subMapFusion.cpp", line 2235, in main [0x555555601305]
2232: std::thread OptThread(&SubMapFusion::globalOptimizationThread, &SubMapF);
2233: std::thread pubLoopThread(&SubMapFusion::publishSCWithCloudThread, &SubMapF);
2234:
>2235: ros::spin();
2236:
2237: pubDesOtherThread.join();
2238: pubMapThread.join();
#17 Object "/opt/ros/noetic/lib/libroscpp.so", at 0x7ffff7f2a21e, in ros::spin()
#16 Object "/opt/ros/noetic/lib/libroscpp.so", at 0x7ffff7f41fce, in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*)
#15 Object "/opt/ros/noetic/lib/libroscpp.so", at 0x7ffff7eee882, in ros::CallbackQueue::callAvailable(ros::WallDuration)
#14 Object "/opt/ros/noetic/lib/libroscpp.so", at 0x7ffff7eed171, in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*)
#13 Object "/opt/ros/noetic/lib/libroscpp.so", at 0x7ffff7f3f138, in ros::SubscriptionQueue::call()
#12 Source "/opt/ros/noetic/include/ros/subscription_callback_helper.h", line 144, in call [0x5555556fe2ca]
141: virtual void call(SubscriptionCallbackHelperCallParams& params)
142: {
143: Event event(params.event, create);
> 144: callback(ParameterAdapter<P>::getParameter(event));
145: }
146:
147: virtual const std::type_info& getTypeInfo()
#11 Source "/usr/include/boost/function/function_template.hpp", line 763, in operator() [0x555555702548]
760: if (this->empty())
761: boost::throw_exception(bad_function_call());
762:
> 763: return get_vtable()->invoker
764: (this->functor BOOST_FUNCTION_COMMA BOOST_FUNCTION_ARGS);
765: }
#10 Source "/usr/include/boost/function/function_template.hpp", line 158, in invoke [0x5555556b57eb]
155: f = reinterpret_cast<FunctionObj*>(function_obj_ptr.data);
156: else
157: f = reinterpret_cast<FunctionObj*>(function_obj_ptr.members.obj_ptr);
> 158: BOOST_FUNCTION_RETURN((f)(BOOST_FUNCTION_ARGS));
159: }
160: };
#9 Source "/usr/include/boost/function/function_template.hpp", line 763, in operator() [0x5555556c1db5]
760: if (this->empty())
761: boost::throw_exception(bad_function_call());
762:
> 763: return get_vtable()->invoker
764: (this->functor BOOST_FUNCTION_COMMA BOOST_FUNCTION_ARGS);
765: }
#8 Source "/usr/include/boost/function/function_template.hpp", line 158, in invoke [0x555555696649]
155: f = reinterpret_cast<FunctionObj>(function_obj_ptr.data);
156: else
157: f = reinterpret_cast<FunctionObj*>(function_obj_ptr.members.obj_ptr);
> 158: BOOST_FUNCTION_RETURN((*f)(BOOST_FUNCTION_ARGS));
159: }
160: };
#7 Source "/usr/include/boost/bind/bind.hpp", line 1306, in operator()<const boost::shared_ptr<const sensor_msgs::PointCloud2<std::allocator
I have the same issue, I got a "segment fault" when I use the "Add_Points" function.
I am also experiencing the same issue:
Any support would be greatly appreciated!
I noticed that if I set the value if 'Minimal_Unbalanced_Tree_Size' to INIFINITY in ikd_tree.h, the segmentation fault error stops happening. I think this could indicate an issue with the re-building process in the second thread. This is not a viable solution since when the tree size increases, the computation time increases exponentially, but could give an idea on where to look for to fix the issue.
I hope this can be useful!
rebuild thread: write Rebuild_Ptr:
add points thread: read Rebuild_Ptr:
This variable was read and written without mutex, leading to a segmentation fault. This is merely my initial hypothesis and has yet to be confirmed.
Experiencing the same issue here. Having the same hypothesis as what @ning-zelin mentioned. A temporary workaround could be:
- comment out the code creating the
rebuild_thread
to disable multi-threading for rebuild; - adjust
Rebuild()
method to always use the plain rebuild pipeline;
which seems work for me currently.
Experiencing the same issue here. Having the same hypothesis as what @ning-zelin mentioned. A temporary workaround could be:
- comment out the code creating the
rebuild_thread
to disable multi-threading for rebuild;- adjust
Rebuild()
method to always use the plain rebuild pipeline;which seems work for me currently. Thanks!! I commeted out the pthread_create( &rebuild_thread, NULL, multi_thread_ptr, ( void * ) this ); Its works now !!