问题描述
在Ubuntu 18.04上跑orbslam2程序,能够顺利运行orbslam2源码,但在自己新增了一段g2o优化的代码后,运行时出现段错误。错误触发于执行优化时:
optimizer.initializeOptimization();
optimizer.optimize(20);
当注释掉这段后,不报段错误了,开始报错“double free or corruption (out)”。
分析
网上大多数g2o段错误的帖子说是编译时--march=native
的设置问题,但我源码的g2o跑得好好的。问题在自己新写的代码上,是朴素的段错误问题,自己写的代码没搞好内存管理。
使用sanitizer运行时动态检查:对g2o和orbslam2的CMakeLists.txt分别添加设置-fsanitize=address -g
。再编译、运行,果然报错,提供了有意义的信息:
==8317==ERROR: AddressSanitizer: heap-use-after-free on address 0x613000643070 at pc 0x7f7e1a42ec4f bp 0x7f7dedb5a6a0 sp 0x7f7dedb5a690
READ of size 8 at 0x613000643070 thread T1
...
#4 0x7f7e1a461d29 in g2o::OptimizableGraph::addEdge(g2o::HyperGraph::Edge*) xxx/ORB_SLAM2-master/Thirdparty/g2o/g2o/core/optimizable_graph.cpp:270
#5 0x7f7e1d6b212b in ORB_SLAM2::Optimizer::hongzhilu_optimize_poseonly(ORB_SLAM2::Map*, unsigned long, unsigned long, bool const&) xxx/ORB_SLAM2-master/src/Optimizer.cc:1335
...
0x6130004eee90 is located 208 bytes inside of 384-byte region [0x6130004eedc0,0x6130004eef40)
freed by thread T1 here:
...
#4 0x7f7e1d6b894c in std::_Sp_counted_ptr_inplace<g2o::VertexSim3Expmap, std::allocator<g2o::VertexSim3Expmap>, (__gnu_cxx::_Lock_policy)2>::_M_destroy() /usr/include/c++/7/bits/shared_ptr_base.h:543
...
previously allocated by thread T1 here:
...
#8 0x7f7e1d6af28f in std::shared_ptr<g2o::VertexSim3Expmap> std::make_shared<g2o::VertexSim3Expmap>() /usr/include/c++/7/bits/shared_ptr.h:707
#9 0x7f7e1d6af28f in ORB_SLAM2::Optimizer::hongzhilu_optimize_poseonly(ORB_SLAM2::Map*, unsigned long, unsigned long, bool const&) xxx/ORB_SLAM2-master/src/Optimizer.cc:1281
...
自己新写的函数里,节点智能指针的空间申请和释放,将边加入优化器时读取……
结论
学艺不精,自作聪明地把源码中动态构造节点的普通指针g2o::VertexSim3Expmap* VSim3
改写成智能指针std::shared_ptr<g2o::VertexSim3Expmap> VSim3
,导致代码块退出时节点内存跟着智能指针一同释放,而节点在被释放前加入了优化器,后面发生了对节点已释放内存的访问。
改回普通指针,问题就解决了。