raulmur / ORB_SLAM2

Real-Time SLAM for Monocular, Stereo and RGB-D Cameras, with Loop Detection and Relocalization Capabilities
Other
9.48k stars 4.7k forks source link

Debug build: systematic crash #341

Open crey0 opened 7 years ago

crey0 commented 7 years ago

After dealing with various crashes when trying to adapt the ROS example code for my purpose, I built the library with debug symbols enabled, ie changing -DCMAKE_BUILD_TYPE=Release to -DCMAKE_BUILD_TYPE=Debug everywhere in build.sh.

Even with the provided examples (in this case the EUROC dataset), the process systematically crashes during the first optimization run (I guess when the first two keyframes are chosen), somewhere in the g2o library, often when doing Eigen computations. I tried compiling with GCC and clang (I had to change includes from stdint-gcc.h to stdint.h in some headers to be able to compile with clang), although the error is not the same in both cases the crash is systematic.

My setup: Ubuntu 16.04 cmake 3.5.1 Eigen 3.2.92 gcc 5.4.0 clang 3.8.0-2ubuntu4

I run with the following command (I tried the same without gdb - same thing happens):

gdb -ex run --args ./Examples/Monocular/mono_euroc Vocabulary/ORBvoc.txt Examples/Monocular/EuRoC.yaml ../EUROC_dataset/mav0/cam0/data Examples/Monocular/EuRoC_TimeStamps/MH05.txt

A few examples with backtraces:

Example with gcc:

New Map created with 144 points computeActiveErrors(): found NaN in error for edge 0x6294a80 [...] computeActiveErrors(): found NaN in error for edge 0x5fc5dc0 buildSystem(): NaN within Jacobian for edge 0x6294a80 for vertex 0 [...] buildSystem(): NaN within Jacobian for edge 0x5fc57c0 for vertex 0 void g2o::SparseOptimizer::update(const double): Update contains a nan for vertex 1
[...] void g2o::SparseOptimizer::update(const double
): Update contains a nan for vertex 145 computeActiveErrors(): found NaN in error for edge 0x6294a80 [...] computeActiveErrors(): found NaN in error for edge 0x5fc5dc0

mono_euroc: [...]/ORB_SLAM2/Thirdparty/g2o/g2o/types/../core/base_vertex.h:97: void g2o::BaseVertex<D, T>::pop() [with int D = 6; T = g2o::SE3Quat]: Assertion `!_backup.empty()' failed. Thread 1 "mono_euroc" received signal SIGABRT, Aborted. 0x00007ffff64a6428 in __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:54 54 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory. (gdb) bt

0 0x00007ffff64a6428 in __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:54

1 0x00007ffff64a802a in __GI_abort () at abort.c:89

2 0x00007ffff649ebd7 in __assert_fail_base (fmt=, assertion=assertion@entry=0x7ffff5eb6213 "!_backup.empty()",

file=file@entry=0x7ffff5eb61a0 "[...]/ORB_SLAM2/Thirdparty/g2o/g2o/types/../core/base_vertex.h", line=line@entry=97, 
function=function@entry=0x7ffff5eb6f00 <g2o::BaseVertex<6, g2o::SE3Quat>::pop()::__PRETTY_FUNCTION__> "void g2o::BaseVertex<D, T>::pop() [with int D = 6; T = g2o::SE3Quat]") at assert.c:92

3 0x00007ffff649ec82 in __GI___assert_fail (assertion=0x7ffff5eb6213 "!_backup.empty()",

file=0x7ffff5eb61a0 "[...]/ORB_SLAM2/Thirdparty/g2o/g2o/types/../core/base_vertex.h", line=97, 
function=0x7ffff5eb6f00 <g2o::BaseVertex<6, g2o::SE3Quat>::pop()::__PRETTY_FUNCTION__> "void g2o::BaseVertex<D, T>::pop() [with int D = 6; T = g2o::SE3Quat]") at assert.c:101

4 0x00007ffff5d68935 in g2o::BaseVertex<6, g2o::SE3Quat>::pop (this=0x5fb6f60) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/types/../core/base_vertex.h:97

5 0x00007ffff5e8f4a1 in g2o::SparseOptimizer::pop (this=0x7ffffffb2660, vlist=std::vector of length 91, capacity 91 = {...})

at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:525

6 0x00007ffff5e8f9c0 in g2o::SparseOptimizer::pop (this=0x7ffffffb2660) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:607

7 0x00007ffff5e9f5cf in g2o::OptimizationAlgorithmLevenberg::solve (this=0x5fb6c60, iteration=0, online=false)

at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp:146

8 0x00007ffff5e8e940 in g2o::SparseOptimizer::optimize (this=0x7ffffffb2660, iterations=20, online=false) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:388

9 0x00007ffff7b2e5f8 in ORB_SLAM2::Optimizer::BundleAdjustment (vpKFs=std::vector of length 2, capacity 2 = {...}, vpMP=std::vector of length 89, capacity 89 = {...}, nIterations=nIterations@entry=20,

pbStopFlag=pbStopFlag@entry=0x0, nLoopKF=nLoopKF@entry=0, bRobust=bRobust@entry=true) at [...]/ORB_SLAM2/src/Optimizer.cc:188

10 0x00007ffff7b2ec07 in ORB_SLAM2::Optimizer::GlobalBundleAdjustemnt (pMap=0x5ee1380, nIterations=nIterations@entry=20, pbStopFlag=pbStopFlag@entry=0x0, nLoopKF=nLoopKF@entry=0, bRobust=bRobust@entry=true)

at [...]/ORB_SLAM2/src/Optimizer.cc:45

11 0x00007ffff7acb190 in ORB_SLAM2::Tracking::CreateInitialMapMonocular (this=this@entry=0x5ee56f0) at [...]/ORB_SLAM2/src/Tracking.cc:686

12 0x00007ffff7acc4c4 in ORB_SLAM2::Tracking::MonocularInitialization (this=this@entry=0x5ee56f0) at [...]/ORB_SLAM2/src/Tracking.cc:632

13 0x00007ffff7acf1b7 in ORB_SLAM2::Tracking::Track (this=this@entry=0x5ee56f0) at [...]/ORB_SLAM2/src/Tracking.cc:284

14 0x00007ffff7ad10f7 in ORB_SLAM2::Tracking::GrabImageMonocular (this=0x5ee56f0, im=..., timestamp=@0x7fffffffd708: 1403638523.6278296) at [...]/ORB_SLAM2/src/Tracking.cc:262

15 0x00007ffff7abac2c in ORB_SLAM2::System::TrackMonocular (this=this@entry=0x7fffffffd930, im=..., timestamp=@0x7fffffffd708: 1403638523.6278296)

at [...]/ORB_SLAM2/src/System.cc:260

16 0x0000000000403449 in main (argc=, argv=) at [...]/ORB_SLAM2/Examples/Monocular/mono_euroc.cc:90

And with clang: New Map created with 119 points terminate called after throwing an instance of 'std::bad_alloc' what(): std::bad_alloc

Thread 1 "mono_euroc" received signal SIGABRT, Aborted. 0x00007fffe86eb428 in __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:54 54 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory. (gdb) bt

0 0x00007fffe86eb428 in __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:54

1 0x00007fffe86ed02a in __GI_abort () at abort.c:89

2 0x00007fffe902d84d in __gnu_cxx::__verbose_terminate_handler() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

3 0x00007fffe902b6b6 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

4 0x00007fffe902b701 in std::terminate() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

5 0x00007fffe902b919 in __cxa_throw () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

6 0x00007ffff7aac65f in Eigen::internal::throw_std_bad_alloc () at /usr/include/eigen3/Eigen/src/Core/util/Memory.h:92

7 0x00007fffe97cee69 in Eigen::internal::aligned_malloc (size=18446744073709551552) at /usr/include/eigen3/Eigen/src/Core/util/Memory.h:236

8 0x00007fffe98103c5 in Eigen::aligned_allocator::allocate (this=0xd56e410, num=288230376151711743) at /usr/include/eigen3/Eigen/src/Core/util/Memory.h:819

9 0x00007fffe981036c in gnu_cxx::__alloc_traits<Eigen::aligned_allocator_indirection >::allocate (a=..., __n=288230376151711743)

at /usr/bin/../lib/gcc/x86_64-linux-gnu/5.4.0/../../../../include/c++/5.4.0/ext/alloc_traits.h:182

10 0x00007fffe9810313 in std::_Vector_base<g2o::SE3Quat, Eigen::aligned_allocator_indirection >::_M_allocate (this=0xd56e410, __n=288230376151711743)

at /usr/bin/../lib/gcc/x86_64-linux-gnu/5.4.0/../../../../include/c++/5.4.0/bits/stl_vector.h:170

11 0x00007fffe986adf4 in std::vector<g2o::SE3Quat, Eigen::aligned_allocator_indirection >::_M_insert_aux (this=0xd56e410, __position=<error reading variable: Cannot access memory at address 0x0>,

__x=...) at /usr/bin/../lib/gcc/x86_64-linux-gnu/5.4.0/../../../../include/c++/5.4.0/bits/vector.tcc:353

12 0x00007fffe986acd1 in std::vector<g2o::SE3Quat, Eigen::aligned_allocator_indirection >::push_back (this=0xd56e410, __x=...)

at /usr/bin/../lib/gcc/x86_64-linux-gnu/5.4.0/../../../../include/c++/5.4.0/bits/stl_vector.h:925

13 0x00007fffe986ac58 in std::stack<g2o::SE3Quat, std::vector<g2o::SE3Quat, Eigen::aligned_allocator > >::push (this=0xd56e410, __x=...)

at /usr/bin/../lib/gcc/x86_64-linux-gnu/5.4.0/../../../../include/c++/5.4.0/bits/stl_stack.h:190

14 0x00007fffe97f9210 in g2o::BaseVertex<6, g2o::SE3Quat>::push (this=0xd56e320) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/types/../core/base_vertex.h:96

15 0x00007fffe995d6a4 in g2o::SparseOptimizer::push (this=0x7ffffff8d8b8, vlist=std::vector of length 121, capacity 121 = {...})

at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:519

16 0x00007fffe995dc51 in g2o::SparseOptimizer::push (this=0x7ffffff8d8b8) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:602

17 0x00007fffe996f5e2 in g2o::OptimizationAlgorithmLevenberg::solve (this=0xd56e010, iteration=0, online=false)

at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp:103

18 0x00007fffe995cafb in g2o::SparseOptimizer::optimize (this=0x7ffffff8d8b8, iterations=20, online=false) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:388

19 0x00007ffff7b11b5f in ORB_SLAM2::Optimizer::BundleAdjustment (vpKFs=..., vpMP=..., nIterations=, pbStopFlag=, nLoopKF=, bRobust=)

at [...]/ORB_SLAM2/src/Optimizer.cc:188

20 0x00007ffff7b110ef in ORB_SLAM2::Optimizer::GlobalBundleAdjustemnt (pMap=0xd4c0930, nIterations=20, pbStopFlag=0x0, nLoopKF=0, bRobust=true)

at [...]/ORB_SLAM2/src/Optimizer.cc:45

21 0x00007ffff7ac0059 in ORB_SLAM2::Tracking::CreateInitialMapMonocular (this=) at [...]/ORB_SLAM2/src/Tracking.cc:686

22 0x00007ffff7abcee2 in ORB_SLAM2::Tracking::MonocularInitialization (this=) at [...]/ORB_SLAM2/src/Tracking.cc:632

23 0x00007ffff7ab7c9b in ORB_SLAM2::Tracking::Track (this=0xd4c3570) at [...]/ORB_SLAM2/src/Tracking.cc:284

24 0x00007ffff7abb9b9 in ORB_SLAM2::Tracking::GrabImageMonocular (this=0xd4c3570, im=..., timestamp=@0x7fffffffd5a8: 1403638522.1278296) at [...]/ORB_SLAM2/src/Tracking.cc:262

25 0x00007ffff7aa5d1e in ORB_SLAM2::System::TrackMonocular (this=, im=..., timestamp=) at [...]/ORB_SLAM2/src/System.cc:260

26 0x000000000040779a in main (argc=, argv=) at [...]/ORB_SLAM2/Examples/Monocular/mono_euroc.cc:90

Another example: New Map created with 73 points

Thread 1 "mono_euroc" received signal SIGSEGV, Segmentation fault. Eigen::internal::pstore<double, double vector(4)>(double*, double vector(4) const&) (to=, from=...) at /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h:244 244 template<> EIGEN_STRONG_INLINE void pstore(double* to, const Packet4d& from) { EIGEN_DEBUG_ALIGNED_STORE _mm256_store_pd(to, from); } (gdb) bt

0 Eigen::internal::pstore<double, double vector(4)>(double*, double vector(4) const&) (to=, from=...) at /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h:244

1 Eigen::internal::pstoret<double, double vector(4), 32>(double*, double vector(4) const&) (to=, from=...) at /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h:486

2 Eigen::internal::assign_op::assignPacket<32, double vector(4)>(double*, double vector(4) const&) const (this=, a=, b=...)

at /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h:28

3 Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, Eigen::internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, Eigen::internal::assign_op, 0>::assignPacket<32, 32, double __vector(4)>(long) (this=, index=)

at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:598

4 Eigen::internal::dense_assignment_loop<Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Matrix<double, -1, 1, 0, -1, 1> >, Eigen::internal::evaluator<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> > >, Eigen::internal::assign_op, 0>, 3, 0>::run (kernel=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:386

5 Eigen::internal::call_dense_assignment_loop<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> >, Eigen::internal::assign_op > (dst=..., src=..., func=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:653

6 Eigen::internal::Assignment<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> >, Eigen::internal::assign_op, Eigen::internal::Dense2Dense, double>::run (dst=..., src=..., func=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:790

7 Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> >, Eigen::internal::assign_op > (dst=..., src=..., func=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747

8 0x00007fffef3bedf9 in Eigen::internal::call_assignment<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> >, Eigen::internal::assign_op > (dst=..., src=..., func=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:712

9 0x00007fffef3bedbf in Eigen::internal::call_assignment<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > (

dst=..., src=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:693

10 0x00007fffef3bed6c in Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::_set<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > (

this=0x63387f0, other=...) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:682

11 0x00007fffef3bed28 in Eigen::Matrix<double, -1, 1, 0, -1, 1>::operator=<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op, Eigen::Matrix<double, -1, 1, 0, -1, 1> > > (this=0x63387f0,

other=...) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:225

12 0x00007fffef3becf4 in Eigen::DenseBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::setConstant (this=0x63387f0, val=@0x7ffffff8d210: 0) at /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h:338

13 0x00007fffef3bcf31 in Eigen::DenseBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::setZero (this=0x63387f0) at /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h:506

14 0x00007fffef3bcad9 in g2o::JacobianWorkspace::allocate (this=0x7ffffff8db58) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp:54

15 0x00007fffef3a7021 in g2o::SparseOptimizer::initializeOptimization (this=0x7ffffff8da58, vset=std::set with 75 elements = {...}, level=0)

at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:211

16 0x00007fffef3a6f3f in g2o::SparseOptimizer::initializeOptimization (this=0x7ffffff8da58, level=0) at [...]/ORB_SLAM2/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp:203

17 0x00007ffff7b18d1c in ORB_SLAM2::Optimizer::BundleAdjustment (vpKFs=..., vpMP=..., nIterations=, pbStopFlag=, nLoopKF=, bRobust=)

at [...]/ORB_SLAM2/src/Optimizer.cc:187

18 0x00007ffff7b1830f in ORB_SLAM2::Optimizer::GlobalBundleAdjustemnt (pMap=0x5ee9fc0, nIterations=20, pbStopFlag=0x0, nLoopKF=0, bRobust=true)

at [...]/ORB_SLAM2/src/Optimizer.cc:45

19 0x00007ffff7acadfc in ORB_SLAM2::Tracking::CreateInitialMapMonocular (this=) at [...]/ORB_SLAM2/src/Tracking.cc:686

20 0x00007ffff7ac7eaf in ORB_SLAM2::Tracking::MonocularInitialization (this=) at [...]/ORB_SLAM2/src/Tracking.cc:632

21 0x00007ffff7ac2fcb in ORB_SLAM2::Tracking::Track (this=0x5eea8b0) at [...]/ORB_SLAM2/src/Tracking.cc:284

22 0x00007ffff7ac6ab9 in ORB_SLAM2::Tracking::GrabImageMonocular (this=0x5eea8b0, im=..., timestamp=@0x7fffffffd798: 1403638522.2778294) at [...]/ORB_SLAM2/src/Tracking.cc:262

23 0x00007ffff7ab1c8e in ORB_SLAM2::System::TrackMonocular (this=, im=..., timestamp=) at [...]/ORB_SLAM2/src/System.cc:260

24 0x0000000000403477 in main (argc=, argv=) at [...]/ORB_SLAM2/Examples/Monocular/mono_euroc.cc:90

arunabhcode commented 7 years ago

I bypassed it by going in the g2o cmakelists and the orb slam cmakelists and removing -march=native. Hope it works for you too.

bcm0 commented 7 years ago

Recompiling g2o and orb_slam without "-march=native" didn't work for me. I use opencv3 (native, not the ros package) and try to run

"Examples/Monocular/mono_tum /home/user/git/ORB_SLAM2/Vocabulary/ORBvoc.txt Examples/Monocular/TUM1.yaml Examples/rgbd_dataset_freiburg1_xyz/"

Error:

Framebuffer with requested attributes not available. Using available framebuffer. You may see visual artifacts. New Map created with 89 points. Illegal instruction (core dumped)

Alkaid-Benetnash commented 7 years ago

Hi, I have encountered with similar problems. If I don't compile ORB_SLAM2 with '-march=native' and g2o is compiled as default (with '-march=native'). There will be a segmentation fault happen in g2o when doing bundle adjustment. In my case, the backtrace looks like:

-------
Start processing sequence ...
Images in the sequence: 798

New Map created with 87 points
*** Error in `./mono_tum': double free or corruption (out): 0x000055aaea9f95b0 ***
======= Backtrace: =========
/usr/lib/libc.so.6(+0x72bdd)[0x7f3e9ae1fbdd]
/usr/lib/libc.so.6(+0x792ec)[0x7f3e9ae262ec]
/usr/lib/libc.so.6(+0x7a6d1)[0x7f3e9ae276d1]
Thirdparty/g2o/lib/libg2o.so(_ZN3g2o15VertexSE3ExpmapD0Ev+0x27)[0x7f3e9bc761d7]
Thirdparty/g2o/lib/libg2o.so(_ZN3g2o10HyperGraph5clearEv+0x88)[0x7f3e9bc91a08]
Thirdparty/g2o/lib/libg2o.so(_ZN3g2o16OptimizableGraphD1Ev+0x24)[0x7f3e9bc9bda4]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM29Optimizer16BundleAdjustmentERKSt6vectorIPNS_8KeyFrameESaIS3_EERKS1_IPNS_8MapPointESaIS9_EEiPbmb+0xabd)[0x7f3eaa00795d]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM29Optimizer22GlobalBundleAdjustemntEPNS_3MapEiPbmb+0x67)[0x7f3eaa007c97]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM28Tracking25CreateInitialMapMonocularEv+0x379)[0x7f3ea9f933a9]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM28Tracking23MonocularInitializationEv+0x78f)[0x7f3ea9f941ef]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM28Tracking5TrackEv+0x6e)[0x7f3ea9f96f6e]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM28Tracking18GrabImageMonocularERKN2cv3MatERKd+0x1de)[0x7f3ea9f99b9e]
lib/libORB_SLAM2.so(_ZN9ORB_SLAM26System14TrackMonocularERKN2cv3MatERKd+0xfe)[0x7f3ea9f8286e]

So there seems to some magic about '-march=native'. I hope someone can explain it more clearly.

My system information:

cpu: Intel(R) Core(TM) i7-7700HQ
compiler: GCC 7.1.1
crey0 commented 7 years ago

Indeed compiling without -march=native seems to work for me. It seems to provoke or reveal strange memory corruptions involving Eigen happening in g2o.

mromanelli9 commented 6 years ago

This worked also for me. Thanks guys.

felixchenfy commented 6 years ago

"removing -march=native" works for me too. Thanks!
But could you explain why this solves the problem @arunabhcode? Thanks again.

crey0 commented 6 years ago

@felixchenfy I can give you a few directions to look for but no definite answer. This seems to be a problem involving the usage of Eigen in g2o and maybe the linking with ORB_SLAM. Eigen optimizes a lot the codepath, furthermore '-march=native' enables even more optimizations. In particular if your CPU support AVX intructions set, Eigen will use it. AVX requires 32 bytes alignement, and I think SSE only 16 byte. Therefore Eigen will assume everything it uses is 32 byte aligned, but it may not be the case if not allocated properly (also, some compiler versions were know to have alignment issues but all references I found were from a few years ago).

To add to the complexity of the thing, some Eigen options, regardless of the '-march=native' flag, can be disabled using preprocessor directives. See https://eigen.tuxfamily.org/dox/TopicPreprocessorDirectives.html#TopicPreprocessorDirectivesPerformance for a list of the possible options. In particular the values of EIGEN_MAX_ALIGN_BYTES and EIGEN_MAX_STATIC_ALIGN_BYTES are very important (if they are not defined, Eigen chooses an appropriate value).

Finally because g2o is a shared library, when you link with it you should make sure that you compile with the exact same options than g2o, especially for Eigen. If not it can lead to either memory corruption or assertions failure in the Eigen.

So the picture is quite clear, but I did not investigate to see exactly what happens. To add to the problem fiddling with "-march=native" worked for me only with gcc, still not working with clang. Which is why I think there is still the possibility of something deeper than compiler options mismatch.

So the probable causes (which may not be mutually exclusive) :

felixchenfy commented 6 years ago

Wow, it's such a detailed explanation. Thank you so much crey0!

zdxiao commented 6 years ago

Deleting "-march=native" also works for me. Thanks a lot.

tgroll commented 5 years ago

I had the same problem within our project. I have deleted the "-march=native" option. Now, it works.

We use the version of eigen3 which is coming with ubuntu 16.04

s-hemer commented 5 years ago

To add to @tgroll s comment: we had that issue on both Intel i7-4810MQ and Intel i7-8700K CPU using 16.04's gcc 5.4.0.

MapleMrming commented 5 years ago

Deleting "-march=native" in g2o cmakelists and the orb slam cmakelists also works for me. Thank you so much.

WeiYongqiang55 commented 5 years ago

Deleting "-march=native" in g2o cmakelists and the orb slam cmakelists also works for me too. Thank you so much. ubuntu18

arunabhcode commented 5 years ago

@crey0 @felixchenfy to build on top of what crey0 said, this bug is caused because of how gcc selects symbols, so if g2o has eigen symbols compiled with a different instruction set than the eigen symbols compiled in ORB than since gcc will consistently select one symbol, it will either cause a seg fault inside ORB SLAM or inside g2o. Hope that helps!

SupRichard8 commented 5 years ago

Recompiling g2o and orb_slam without "-march=native" didn't work for me. I use opencv3 (native, not the ros package) and try to run

"Examples/Monocular/mono_tum /home/user/git/ORB_SLAM2/Vocabulary/ORBvoc.txt Examples/Monocular/TUM1.yaml Examples/rgbd_dataset_freiburg1_xyz/"

Error:

Framebuffer with requested attributes not available. Using available framebuffer. You may see visual artifacts. New Map created with 89 points. Illegal instruction (core dumped)

Bro,I have met the same problem,how did you solve this?

BJM666 commented 5 years ago

Recompiling g2o and orb_slam without "-march=native" didn't work for me. I use opencv3 (native, not the ros package) and try to run

"Examples/Monocular/mono_tum /home/user/git/ORB_SLAM2/Vocabulary/ORBvoc.txt Examples/Monocular/TUM1.yaml Examples/rgbd_dataset_freiburg1_xyz/"

Error:

Framebuffer with requested attributes not available. Using available framebuffer. You may see visual artifacts. New Map created with 89 points. Illegal instruction (core dumped)

It didn't work to me,too.I have delete the "-march=native" both in orb_slam and g2o.

nvhungv2k commented 7 months ago

I bypassed it by going in the g2o cmakelists and the orb slam cmakelists and removing -march=native. Hope it works for you too.

thanks. It worked great for me!