moveit segfaults due to eigen
I am running ros melodic on an up to date unstable x86_64 gentoo with ebuilds from the ros-overlay. As far as I am aware the last update of the ebuilds was three days ago. I tested with moveit-0.10.0 as well as the recently released moveit-1.0.0.
So far I have tested gcc-7.3.0, gcc-7.4.0, gcc-8.2.0 and gcc-8.3.0 with binutils-2.31.1 and -2.32 with the same results.
I have tested eigen 3.3.4, 3.3.5 and 3.3.7 against gcc-8.3.0, binutils-2.32 and moveit-1.0.0 with the same results.
Either rviz or move_group will crash somewhere in moveit code with segfaults cause by eigen. I have attached a few crash reports with similar failures.
After reading "Eigen Memory Issues" and "Explanation of the assertion on unaligned arrays" I am aware eigen related segfaults can be caused by mismatched build flags which might be an issue on gentoo. All ros related packages are build with "-O2 -pipe -march=native -mtune=native -Wall -g -ggdb". I also created a local catkin workspace where I rebuild industrialcore, motoman, moveit, moveitvisual_tools and rviz with the same build flags and both -std=c++11 and -std=c++14 with no change in outcome.
I used to be able to run the same commands i tested with eigen-3.2.8 and moveit-0.10.0 but since moveit-1.0.0 requires eigen-3.3 and eigen-3.2 has been deprecated in gentoo I am reluctant to downgrade back to that. Blender and meshlab which also depend on eigen do run without segfaults.
Since I am not fully certain if this is a build system error or an error in moveit I haven't filled an issue on github yet.
When i compile moveit_core with "-Wall" set I get this suspicious warning:
/var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_state/src/robot_state.cpp: In member function 'void moveit::core::RobotState::copyFrom(const moveit::core::RobotState&)':
/var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_state/src/robot_state.cpp:161:79: warning: 'void* memcpy(void*, const void*, size_t)' writing to an object of type 'Eigen::Isometry3d' {aka 'class Eigen::Transform<double, 3, 1>'} with no trivial copy-assignment; use copy-assignment or copy-initialization instead [-Wclass-memaccess]
memcpy(variable_joint_transforms_, other.variable_joint_transforms_, bytes);
^
In file included from /usr/include/eigen3/Eigen/Geometry:44,
from /var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_model/include/moveit/robot_model/joint_model.h:47,
from /var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_model/include/moveit/robot_model/joint_model_group.h:41,
from /var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_model/include/moveit/robot_model/robot_model.h:47,
from /var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_state/include/moveit/robot_state/robot_state.h:41,
from /var/tmp/portage/ros-melodic-moveit_core-1.0.0/work/moveit_core-1.0.0/robot_state/src/robot_state.cpp:38:
/usr/include/eigen3/Eigen/src/Geometry/Transform.h:201:7: note: 'Eigen::Isometry3d' {aka 'class Eigen::Transform<double, 3, 1>'} declared here
class Transform
^~~~~~~~~
trace 1:
> roslaunch motoman_sda10f_moveit_config demo.launch
Thread 1 (Thread 0x7f7251ee1240 (LWP 5998)):
[KCrash Handler]
#6 0x00007f72030373f5 in _mm256_store_pd (__A=..., __P=0x55edf39a24d0) at /usr/lib/gcc/x86_64-pc-linux-gnu/8.3.0/include/avxintrin.h:867
#7 Eigen::internal::pstore<double, double __vector(4)>(double*, double __vector(4) const&) (from=..., to=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h:252
#8 Eigen::internal::pstoret<double, double __vector(4), 32>(double*, double __vector(4) const&) (from=..., to=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h:474
#9 Eigen::internal::assign_op<double, double>::assignPacket<32, double __vector(4)>(double*, double __vector(4) const&) const (this=<optimized out>, b=..., a=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h:28
#10 Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > >, Eigen::internal::assign_op<double, double>, 0>::assignPacket<32, 32, double __vector(4)>(long, long) (this=<synthetic pointer>, this=<synthetic pointer>, col=0, row=0) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:652
#11 Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > >, Eigen::internal::assign_op<double, double>, 0>::assignPacketByOuterInner<32, 32, double __vector(4)>(long, long) (inner=0, outer=0, this=<synthetic pointer>) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:666
#12 Eigen::internal::copy_using_evaluator_innervec_CompleteUnrolling<Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > >, Eigen::internal::assign_op<double, double>, 0>, 0, 16>::run (kernel=<synthetic pointer>...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:274
#13 Eigen::internal::dense_assignment_loop<Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > >, Eigen::internal::assign_op<double, double>, 0>, 2, 2>::run (kernel=<synthetic pointer>...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:468
#14 Eigen::internal::call_dense_assignment_loop<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:741
#15 Eigen::internal::Assignment<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double>, Eigen::internal::Dense2Dense, void>::run (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:879
#16 Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:836
#17 Eigen::internal::call_assignment<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double> >(Eigen::Matrix<double, 4, 4, 0, 4, 4>&, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > const&, Eigen::internal::assign_op<double, double> const&, Eigen::internal::enable_if<!Eigen::internal::evaluator_assume_aliasing<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator_traits<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > >::Shape>::value, void*>::type) (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:804
#18 Eigen::internal::call_assignment<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > > (src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:782
#19 Eigen::PlainObjectBase<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::_set<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > > (other=..., this=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:714
#20 Eigen::Matrix<double, 4, 4, 0, 4, 4>::operator=<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > > (other=..., this=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:225
#21 Eigen::DenseBase<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::setConstant (val=<optimized out>, this=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h:327
#22 Eigen::DenseBase<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::setZero (this=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h:501
#23 Eigen::internal::setIdentity_impl<Eigen::Matrix<double, 4, 4, 0, 4, 4>, true>::run (m=...) at /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h:757
#24 Eigen::MatrixBase<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::setIdentity (this=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h:776
#25 Eigen::Transform<double, 3, 1, 0>::setIdentity (this=0x55edf39a24d0) at /usr/include/eigen3/Eigen/src/Geometry/Transform.h:533
#26 moveit::core::FixedJointModel::computeTransform (this=0x7f71f4023950, transf=...) at /home/user/test_ws/src/moveit/moveit_core/robot_model/src/fixed_joint_model.cpp:94
#27 0x00007f72030b95e3 in moveit::core::RobotState::getJointTransform (joint=<optimized out>, this=0x55edf2446660) at /home/user/test_ws/src/moveit/moveit_core/robot_model/include/moveit/robot_model/joint_model.h:204
#28 moveit::core::RobotState::updateLinkTransformsInternal (this=this@entry=0x55edf2446660, start=<optimized out>) at /home/user/test_ws/src/moveit/moveit_core/robot_state/src/robot_state.cpp:652
#29 0x00007f72030b9a02 in moveit::core::RobotState::updateLinkTransforms (this=this@entry=0x55edf2446660) at /home/user/test_ws/src/moveit/moveit_core/robot_state/src/robot_state.cpp:616
#30 0x00007f72030b9a9c in moveit::core::RobotState::updateCollisionBodyTransforms (this=0x55edf2446660) at /home/user/test_ws/src/moveit/moveit_core/robot_state/src/robot_state.cpp:587
#31 0x00007f72340ba517 in moveit_rviz_plugin::PlanningSceneDisplay::onRobotModelLoaded (this=0x55edf2ef21f0) at /home/user/test_ws/src/moveit/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp:548
#32 0x00007f72343da74c in moveit_rviz_plugin::MotionPlanningDisplay::onRobotModelLoaded (this=0x55edf2ef21f0) at /home/user/test_ws/src/moveit/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp:1123
#33 0x00007f72340bacf3 in boost::function0<void>::operator() (this=0x7ffc57e7ed50) at /usr/include/boost/function/function_template.hpp:673
#34 moveit_rviz_plugin::PlanningSceneDisplay::executeMainLoopJobs (this=0x55edf2ef21f0) at /home/user/test_ws/src/moveit/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp:249
#35 0x00007f72340baf89 in moveit_rviz_plugin::PlanningSceneDisplay::update (this=0x55edf2ef21f0, wall_dt=0.0319799781, ros_dt=0.0319808163) at /home/user/test_ws/src/moveit/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp:618
#36 0x00007f7259d30a01 in rviz::DisplayGroup::update (this=0x55edf24216c0, wall_dt=0.0319799781, ros_dt=0.0319808163) at /home/user/test_ws/src/rviz/src/rviz/display_group.cpp:240
#37 0x00007f7259df2966 in rviz::VisualizationManager::onUpdate (this=0x55edf2412e20) at /home/user/test_ws/src/rviz/src/rviz/visualization_manager.cpp:353
#38 0x00007f725888a4ce in QMetaObject::activate(QObject*, int, int, void**) () from /usr/lib64/libQt5Core.so.5
#39 0x00007f7258895db7 in QTimer::timeout(QTimer::QPrivateSignal) () from /usr/lib64/libQt5Core.so.5
#40 0x00007f725888b03b in QObject::event(QEvent*) () from /usr/lib64/libQt5Core.so.5
#41 0x00007f72596ef451 in QApplicationPrivate::notify_helper(QObject*, QEvent*) () from /usr/lib64/libQt5Widgets.so.5
#42 0x00007f72596f6ad0 in QApplication::notify(QObject*, QEvent*) () from /usr/lib64/libQt5Widgets.so.5
#43 0x00007f7258862f72 in QCoreApplication::notifyInternal2(QObject*, QEvent*) () from /usr/lib64/libQt5Core.so.5
#44 0x00007f72588b1079 in QTimerInfoList::activateTimers() () from /usr/lib64/libQt5Core.so.5
#45 0x00007f72588b18d1 in timerSourceDispatch(_GSource*, int (*)(void*), void*) () from /usr/lib64/libQt5Core.so.5
#46 0x00007f725548a84e in g_main_context_dispatch () from /usr/lib64/libglib-2.0.so.0
#47 0x00007f725548aae8 in g_main_context_iterate.isra () from /usr/lib64/libglib-2.0.so.0
#48 0x00007f725548ab7c in g_main_context_iteration () from /usr/lib64/libglib-2.0.so.0
#49 0x00007f72588b1d33 in QEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib64/libQt5Core.so.5
#50 0x00007f7251842171 in QPAEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib64/libQt5XcbQpa.so.5
#51 0x00007f7258861f4b in QEventLoop::exec(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib64/libQt5Core.so.5
#52 0x00007f7258869db2 in QCoreApplication::exec() () from /usr/lib64/libQt5Core.so.5
#53 0x000055edf1a4c1db in main (argc=<optimized out>, argv=<optimized out>) at /home/user/test_ws/src/rviz/src/rviz/main.cpp:42
[Inferior 1 (process 5998) detached]
trace 2:
> roslaunch moveit_visual_tools demo_rviz.launch
Thread 1 (Thread 0x7f7883d6d240 (LWP 2716)):
[KCrash Handler]
#6 0x00007f7839034a3b in _mm256_store_pd (__A=..., __P=<optimized out>) at /usr/lib/gcc/x86_64-pc-linux-gnu/8.3.0/include/emmintrin.h:166
#7 Eigen::internal::pstore<double, double __vector(4)>(double*, double __vector(4) const&) (from=..., to=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h:252
#8 Eigen::internal::pstoret<double, double __vector(4), 32>(double*, double __vector(4) const&) (from=..., to=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h:474
#9 Eigen::internal::assign_op<double, double>::assignPacket<32, double __vector(4)>(double*, double __vector(4) const&) const (this=<optimized out>, b=..., a=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h:28
#10 Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double>, 0>::assignPacket<32, 32, double __vector(4)>(long, long) (this=<optimized out>, this=<optimized out>, col=<optimized out>, row=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:652
#11 Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double>, 0>::assignPacketByOuterInner<32, 32, double __vector(4)>(long, long) (inner=<optimized out>, outer=<optimized out>, this=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:666
#12 Eigen::internal::copy_using_evaluator_innervec_CompleteUnrolling<Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double>, 0>, 0, 16>::run (kernel=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:274
#13 Eigen::internal::dense_assignment_loop<Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::evaluator<Eigen::Matrix<double, 4, 4, 0, 4, 4> >, Eigen::internal::assign_op<double, double>, 0>, 2, 2>::run (kernel=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:468
#14 Eigen::internal::call_dense_assignment_loop<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::internal::assign_op<double, double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:741
#15 Eigen::internal::Assignment<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::internal::assign_op<double, double>, Eigen::internal::Dense2Dense, void>::run (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:879
#16 Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::internal::assign_op<double, double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:836
#17 Eigen::internal::call_assignment<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::internal::assign_op<double, double> >(Eigen::Matrix<double, 4, 4, 0, 4, 4>&, Eigen::Matrix<double, 4, 4, 0, 4, 4> const&, Eigen::internal::assign_op<double, double> const&, Eigen::internal::enable_if<!Eigen::internal::evaluator_assume_aliasing<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::internal::evaluator_traits<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::Shape>::value, void*>::type) (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:804
#18 Eigen::internal::call_assignment<Eigen::Matrix<double, 4, 4, 0, 4, 4>, Eigen::Matrix<double, 4, 4, 0, 4, 4> > (src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:782
#19 Eigen::PlainObjectBase<Eigen::Matrix<double, 4, 4, 0, 4, 4> >::_set<Eigen::Matrix<double, 4, 4, 0, 4, 4> > (other=..., this=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:714
#20 Eigen::Matrix<double, 4, 4, 0, 4, 4>::operator= (other=..., this=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:208
#21 Eigen::Transform<double, 3, 1, 0>::operator= (other=..., this=<optimized out>) at /usr/include/eigen3/Eigen/src/Geometry/Transform.h:286
#22 moveit::core::FloatingJointModel::computeTransform (this=0x5583d7e89970, joint_values=0x5583d89e2d78, transf=...) at /home/user/test_ws/src/moveit/moveit_core/robot_model/src/floating_joint_model.cpp:220
#23 0x00007f78390b65e3 in moveit::core::RobotState::getJointTransform (joint=<optimized out>, this=0x5583d7dddda0) at /home/user/test_ws/src/moveit/moveit_core/robot_model/include/moveit/robot_model/joint_model.h:204
#24 moveit::core::RobotState::updateLinkTransformsInternal (this=this@entry=0x5583d7dddda0, start=<optimized out>) at /home/user/test_ws/src/moveit/moveit_core/robot_state/src/robot_state.cpp:652
#25 0x00007f78390b6a02 in moveit::core::RobotState::updateLinkTransforms (this=this@entry=0x5583d7dddda0) at /home/user/test_ws/src/moveit/moveit_core/robot_state/src/robot_state.cpp:616
#26 0x00007f78390b6a9c in moveit::core::RobotState::updateCollisionBodyTransforms (this=0x5583d7dddda0) at /home/user/test_ws/src/moveit/moveit_core/robot_state/src/robot_state.cpp:587
#27 0x00007f78682914da in moveit_rviz_plugin::RobotStateDisplay::update (this=0x5583d7e23180, wall_dt=<optimized out>, ros_dt=<optimized out>) at /home/user/test_ws/src/moveit/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp:414
#28 0x00007f788bbbca01 in rviz::DisplayGroup::update (this=0x5583d7ef7c20, wall_dt=0.473727763, ros_dt=0.473739237) at /home/user/test_ws/src/rviz/src/rviz/display_group.cpp:240
#29 0x00007f788bc7e966 in rviz::VisualizationManager::onUpdate (this=0x5583d7e05550) at /home/user/test_ws/src/rviz/src/rviz/visualization_manager.cpp:353
#30 0x00007f788a7164ce in QMetaObject::activate(QObject*, int, int, void**) () from /usr/lib64/libQt5Core.so.5
#31 0x00007f788a721db7 in QTimer::timeout(QTimer::QPrivateSignal) () from /usr/lib64/libQt5Core.so.5
#32 0x00007f788a71703b in QObject::event(QEvent*) () from /usr/lib64/libQt5Core.so.5
#33 0x00007f788b57b451 in QApplicationPrivate::notify_helper(QObject*, QEvent*) () from /usr/lib64/libQt5Widgets.so.5
#34 0x00007f788b582ad0 in QApplication::notify(QObject*, QEvent*) () from /usr/lib64/libQt5Widgets.so.5
#35 0x00007f788a6eef72 in QCoreApplication::notifyInternal2(QObject*, QEvent*) () from /usr/lib64/libQt5Core.so.5
#36 0x00007f788a73d079 in QTimerInfoList::activateTimers() () from /usr/lib64/libQt5Core.so.5
#37 0x00007f788a73d909 in idleTimerSourceDispatch(_GSource*, int (*)(void*), void*) () from /usr/lib64/libQt5Core.so.5
#38 0x00007f788731684e in g_main_context_dispatch () from /usr/lib64/libglib-2.0.so.0
#39 0x00007f7887316ae8 in g_main_context_iterate.isra () from /usr/lib64/libglib-2.0.so.0
#40 0x00007f7887316b7c in g_main_context_iteration () from /usr/lib64/libglib-2.0.so.0
#41 0x00007f788a73dd33 in QEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib64/libQt5Core.so.5
#42 0x00007f78836ce171 in QPAEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib64/libQt5XcbQpa.so.5
#43 0x00007f788a6edf4b in QEventLoop::exec(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib64/libQt5Core.so.5
#44 0x00007f788a6f5db2 in QCoreApplication::exec() () from /usr/lib64/libQt5Core.so.5
#45 0x00005583d6a601db in main (argc=<optimized out>, argv=<optimized out>) at /home/user/test_ws/src/rviz/src/rviz/main.cpp:42
[Inferior 1 (process 2716) detached]
Asked by negril on 2019-03-01 13:16:36 UTC
Answers
This is likely a result of the effort to move from Affine3d to Isometry3d which was merged into melodic last November. @rhaschke or @v4hn could probably comment on this better than I. I would recommend opening an issue on github.
Asked by mlautman on 2019-03-05 15:42:25 UTC
Comments
If I understand you correctly:
- moveit-0.10.0 and eigen-3.2.8 works
- moveit-1.0.0 and eigen-3.3 triggers the compiler warning and segfaults
As we don't test against gentoo systems, could you please verify whether you have the same issue also with moveit-0.10.5 and eigen-3.3, which is before the Isometry3d transition.
I just confirmed that on Ubuntu Bionic with eigen-3.3.4 the compiler gcc-7.3.0 doesn't issue the mentioned warning.
Asked by rhaschke on 2019-03-05 16:04:31 UTC
Comments
The version that worked was moveit-0.10.8 and eigen-3.2.8.
Reading through the patch notes for eigen, they introduced AVX support with version 3.3. Which is enabled with -march=native on my system. AVX requires 32 bit-alignment whereas RobotState enforces 16 bit-alignment here resulting in segfaults.
When I add "-DEIGEN_MAX_ALIGN_BYTES=16 -DEIGEN_UNALIGNED_VECTORIZE=0" to the CXXFLAGS for moveit it will run without issues, as this will create SSE compatible code.
As this is a bug in moveit i will open an issue on github.
@rhaschke that warning was introduced in gcc-8: https://gcc.gnu.org/onlinedocs/gcc/C_002b_002b-Dialect-Options.html#index-Wclass-memaccess.
Asked by negril on 2019-03-06 11:33:23 UTC
Comments
Thanks for tracking this down. Looks like an easy fix.
Asked by rhaschke on 2019-03-06 11:40:35 UTC
I wouldn't say that it's an easy fix, as setting the flags is a stop gap solution. It doesn't stop the underlying problem with the hackish c code in there.
Asked by negril on 2019-03-06 12:11:21 UTC
I didn't thought about using your quick fix. However, the proper fix is easy to realize as well: https://github.com/ros-planning/moveit/pull/1382 Could you please verify this and then approve on github?
Asked by rhaschke on 2019-03-06 15:39:56 UTC
Comments