ORB_SLAM2 闭环检测段错误

问题描述:
  Ubuntu14.04运行正常。Ubuntu 16.04下运行时,检测到闭环后有时会段错误,定位发现断错误出现在CorrectLoop()的红色代码处
void LoopClosing::CorrectLoop()
{
  ...
KeyFrameAndPose CorrectedSim3, NonCorrectedSim3; CorrectedSim3[mpCurrentKF]=mg2oScw; cv::Mat Twc = mpCurrentKF->GetPoseInverse();

  ...
}

 

问题原因:

  在CorrectLoop()中使用了一个叫KeyFrameAndPose的数据类型,这个数据结构中会创建Eigen对象,根据Eigen文档,调用Eigen对象的数据结构需要使用Eigen的字节对齐,在LoopCloing中加入字节对齐后问题消失。至于为什么没对齐会报错,我也不知道...

 

解决方法:

  include/LoopClosing.h,加入红色部分(使用Eigen中的方式进行字节对齐)

class LoopClosing
{
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

    typedef pair<set<KeyFrame*>,int> ConsistentGroup;
    ...
};

 

posted @ 2016-08-23 15:18  shishiteng  阅读(1540)  评论(0编辑  收藏  举报