Open YongshuaiZ opened 1 month ago
该问题曾参考: https://github.com/raulmur/ORB_SLAM2/pull/844 https://github.com/RainerKuemmerle/g2o/pull/314 鉴于你所述情况,有以下建议:
-march=native
,重新编译g2o和slam主程序,确认效果;-march=native
,重新编译g2o和slam主程序,确认效果;-march=native
问题,重新安装/编译PCL库并再次重复进行1、2步骤;
(检查libsg-slam.so库的pcl引用库可使用ldd libsg-slam.so | grep pcl
命令)
(可参考 https://github.com/introlab/rtabmap/issues/685#issuecomment-767131923 等类似issue)
期待你的进展。
作者你好,我在最后一步运行时出现 Segmentation fault 问题,我已经将第三方库和主目录下的 -march=native 去掉了,但还是报错,同时我运行了 原有的ORB-SLAM2,发现没有这个问题,用gdb调试后发现错误出现在 g2o部分,虽有已经看到有人提过这个问题了,但自己尝试后依然无法解决,想问下应该怎么解决?
Thread 1 "sg_slam_tum" received signal SIGSEGV, Segmentation fault. 0x00007ffff3a11518 in g2o::EdgeSE3ProjectXYZOnlyPose::linearizeOplus() () from /home/zhu/SlamProjects/Openloris-Scene/SG-SLAM/src/sg-slam/Thirdparty/g2o/lib/libg2o.so (gdb) bt
0 0x00007ffff3a11518 in g2o::EdgeSE3ProjectXYZOnlyPose::linearizeOplus() ()
1 0x00007ffff7723088 in g2o::BlockSolver<g2o::BlockSolverTraits<6, 3> >::buildSystem() ()
2 0x00007ffff3a561c9 in g2o::OptimizationAlgorithmLevenberg::solve(int, bool) ()
3 0x00007ffff3a4ec3c in g2o::SparseOptimizer::optimize(int, bool) ()
4 0x00007ffff76fba4d in ORB_SLAM2::Optimizer::PoseOptimization(ORB_SLAM2::Frame*) ()
5 0x00007ffff76b12ee in ORB_SLAM2::Tracking::TrackReferenceKeyFrame() ()
6 0x00007ffff76b58c5 in ORB_SLAM2::Tracking::Track() ()
7 0x00007ffff76b6695 in ORB_SLAM2::Tracking::GrabImageRGBD(cv::Mat const&, cv::Mat const&, double const&) ()
8 0x00007ffff769e729 in ORB_SLAM2::System::TrackRGBD(cv::Mat const&, cv::Mat const&, double const&) ()
9 0x0000555555564747 in main ()