ORB-SLAM3源码阅读笔记6:IMU初始化状态的切换与分析

Nov 16,2021   5960 words   22 min

Tags: SLAM

1.IMU初始化状态

1.1 在哪里被定义

在ORB-SLAM3中,IMU的初始化状态主要在Map类中被定义。在Map.h文件中定义了protected类型的mbImuInitialized变量用于记录IMU是否初始化成功,如下图所示。 可以看到,在ORB-SLAM3的架构中,IMU状态变量是和Map紧密关联的,而这在一定程度上也就导致了IMU和Map的耦合,不易分开。

1.2 在哪里赋初值

既然mbImuInitialized是Map类的成员变量,因此自然在Map的构造函数中会被赋初值。事实上也是如此,在ORB-SLAM3中Map有两个重载的构造函数,如下。 在这两个构造函数中都对mbImuInitialized赋初值,且默认都为false,也就对应IMU没有初始化的状态。

1.3 在哪里被修改

在定义和赋初值之后,自然需要找到它又在哪里被赋值。利用CLion的“Find Usages”功能,可以很容易找到其在Map类函数中被赋值的地方,如下所示。 可以看到主要是两个函数:clear()SetImuInitialized()。这两个函数其实是对应的,一个是将其设为false,另一个则恰恰相反,将其设为true。从这里也可以看出,当调用Map类的clear()成员函数时,当前地图的相关成员变量就会被重新设为默认值(比如这里的mbImuInitialized被设为false)。

1.4 在哪里被调用

最后,需要寻找的是在Map类中,哪些函数读取或者调用了mbImuInitialized。类似的,通过“Find Usages”功能,可以找到1处,如下所示。 这唯一的一处就是Map类的isImuInitialized()函数,该函数会返回当前地图的IMU的初始化状态。

2.Map类的进一步封装

通过上面的分析可以看出,IMU的初始化状态主要和Map类的函数有关。而在ORB-SLAM3中,又有多地图的概念,因此在Map类的基础上又封装了Atlas类。在Atlas类中有对应的函数(SetImuInitialized()函数、clearMap()函数和isImuInitialized()函数)来给当前Map的mbImuInitialized成员变量进行赋值或访问(对应于Map类的SetImuInitialized()函数、clear()函数和isImuInitialized()函数)。Atlas类中的函数如下。

3.Atlas成员函数调用

在前面说了,系统中对于IMU初始化状态的修改和访问主要是通过Atlas类的SetImuInitialized()函数和isImuInitialized()函数实现,所以,我们还是可以通过“Find Usages”功能,找到这两个函数被调用的地方。

3.1 SetImuInitialized()函数

对于SetImuInitialized()函数而言,其被调用的地方如下。 可以看到,整个系统中只有在LocalMapping类的InitializeIMU()成员函数中被调用。我们可以进一步进入函数查看,如下。 到1399行之前,此时系统已经对IMU进行了初始化,但是还没有对地图中的IMU初始化状态进行更新。所以可以看到,系统首先会对Atlas中当前地图的IMU初始化状态做判断,如果没有初始化的话,就调用Atlas类的SetImuInitialized()成员函数将当前地图的IMU初始化状态设为true。

3.2 clearMap()函数

对于clearMap()函数而言,其被调用的地方如下。 可以看到只在Tracking类的ResetActiveMap()函数中被调用了,具体代码如下所示。 执行完这一行以后,不仅地图重置了,IMU的初始化状态也重置了。

3.3 isImuInitialized()函数

对于isImuInitialized()函数而言,其被调用的地方如下。 可以看到,主要是在LocalMapping类的InitializeIMU()函数、KeyFameCulling()函数;MapDrawer类的DrawKeyFrames()函数;System类的GetTimeFromIMUInit()函数、isLost()函数;Tracking类的CreateNewKeyFrame()函数、SearchLocalPoints()函数、Track()函数、TrackLocalMap()函数、TrackWIthMotionModel()函数、UpdateLocalKeyFrames()函数;Viewer类的Run()函数。可以看到,和我们相关的、重要的函数存在Tracking类中。下面我们会对LocalMapping、System、Tracking类中的相关函数进行简单的分析。

(1) LocalMapping类中的isImuInitialized()函数调用

如下图所示,在LocalMapping类中,主要是在InitializeIMU()函数、KeyFameCulling()函数中调用。 简单列举如下。 可以看到对于第二个情况,当发现地图的IMU初始化状态不OK的时候,就调用了SetImuInitialized()函数进行赋值。

(2) System类中的isImuInitialized()函数调用

在System类中的调用情况如下。 首先在GetTimeFromIMUInit()函数中,就会判断是否初始化完成,如下图所示。 另一处调用就是在isLost()函数中,如下图所示。

(3) Tracking类中的isImuInitialized()函数调用

相较于前两个类,在Tracking类中有较多的调用,如下图所示。 首先是在CreateNewKeyFrame()函数中的调用,如下图所示。 然后是在SearchLocalPoints()函数中有两次调用,如下图所示。 然后是在Track()函数中的调用,如下所示。 TrackLocalMap()函数中的调用,如下所示。 可以看到,这里根据地图中IMU初始化的不同状态进入了不同的优化函数分支。在TrackWithMotionModel()函数中调用如下所示。 和上面类似的,系统会根据IMU的初始化状态决定是用IMU还是视觉来跟踪。最后,在UpdateLocalKeyFrames()函数中,也进行了调用。

4.IMU初始状态变化分析

上面我们分析了IMU初始化这个状态在整个系统中的调用情况。下面我们就从实际运行的角度介绍一下状态变化的逻辑。

4.1 对IMU初始状态的赋值

说起来也非常简单:首先最核心的部分是当然是Map类的protected成员变量mbImuInitialized。然后是修改它的两个Map类成员函数clear()SetImuInitialized(),分别对应false和true状态。然后往外一层,到Atlas级别,分别有Atlas类的成员函数clearMap()SetImuInitialized(),对应Map类的两个函数。再往外一层,clearMap()只在Tracking类的ResetActiveMap()函数中被调用,SetImuInitialized()只在LocalMapping类的InitializeIMU()成员函数中被调用。

至此,我们还可以往外找,Tracking类的ResetActiveMap()函数在System类的成员函数ChangeDataset(), TrackMonocular(), TrackRGBD(), TrackStereo()中被调用,如下图所示。 下图展示了在ChangeDataset()中的调用。 除了第一个,其余函数的调用其实是类似的(这里只展示一个单目的),如下所示。 都是在判断确实需要重置地图的时候调用Tracking类的ResetActiveMap()函数进行重置。

而对于LocalMapping类的InitializeIMU()函数,正如这篇博客分析的,其只在LocalMapping的Run()函数中被调用了,如下图所示。 进一步,我们可以看到,这6处调用其实分别对应的是单目或者双目,如下图所示。 这是在Run()函数中第一次调用InitializeIMU()函数对IMU进行初始化。然后在后面又分别调用了两次,如下图所示。

到这一层,我们搜到的相关函数分别是:System类的成员函数ChangeDataset(), TrackMonocular(), TrackRGBD(), TrackStereo(),它们会将IMU初始化状态设为false;LocalMapping的Run()函数,它会将IMU初始化状态设为true。

我们再深挖一层,对于System类的几个函数,其实如果你对ORB-SLAM的接口比较熟悉,它们已经是最外层的封装了,会直接在Main()函数中被调用,如下图所示,展示了EuRoC接口的调用情况。

而对于LocalMapping的Run()函数,其只在System类的构造函数中被调用,如下图所示。 而System类的构造函数,则在Main()函数中直接被调用,如下图所示。

至此,我们就完成了对于IMU初始化状态的追踪,从Map类的成员变量一直追溯到了Main()函数。如果我们用图来表示,就是如下的样子。 你会发现LocalMapping的Run()函数跟IMU的初始化和优化密切相关,所以如果想弄懂IMU的执行逻辑,应该重点关注这个函数。

4.2 对IMU初始状态的访问

当然,上面说的clearMap()还有SetImuInitialized()函数都是对IMU初始化状态的修改。而对于IMU初始化状态的获取,我们同样可以类似的进行追溯。最核心的还是Map类的protected成员变量mbImuIntialized。再往外一层则是Map类的成员函数isImuInitialized(),以返回当前地图IMU的初始化状态。再往外一层则是Atlas类的成员函数isImuInitialized(),功能是一样的。接下来Atlas类成员函数isImuInitialized()的被调用关系就有些复杂了,如下图所示。 而这也是我们在上面重点分析的部分,这里再回顾一下。

  • 在LocalMapping类中,其主要是在InitializeIMU()函数、KeyFameCulling()函数中调用。
  • 在System类中,其主要是在GetTimeFromIMUInit()函数、isLost()函数中调用。
  • 在Tracking类中,其主要是在CreateNewKeyFrame()函数、SearchLocalPoints()函数、Track()函数、TrackLocalMap()函数、TrackWIthMotionModel()函数、UpdateLocalKeyFrames()函数。

这里这些函数并不是同级的调用关系,而且也比较复杂。但我们仍可以尽可能的得到多条“调用链”,如下。

  • LocalMapping::InitializeIMU() → LocalMapping::Run() → System::System() → Main()
  • LocalMapping::KeyFameCulling() → LocalMapping::Run() → System::System() → Main()
  • System::GetTimeFromIMUInit() → System::isFinished()
  • System::isLost() → ×
  • Tracking::CreateNewKeyFrame() → Tracking::Track() → Tracking::GrabImageMonocular/RGBD/Stereo() → System::TrackMonocular/RGBD/Stereo() → Main()
  • Tracking::SearchLocalPoints() → Tracking::TrackLocalMap() → Tracking::Track() → Tracking::GrabImageMonocular/RGBD/Stereo() → System::TrackMonocular/RGBD/Stereo() → Main()
  • Tracking::Track() → Tracking::GrabImageMonocular/RGBD/Stereo() → System::TrackMonocular/RGBD/Stereo() → Main()
  • Tracking::TrackLocalMap() → Tracking::Track() → Tracking::GrabImageMonocular/RGBD/Stereo() → System::TrackMonocular/RGBD/Stereo() → Main()
  • Tracking::TrackWIthMotionModel() → Tracking::Track() → Tracking::GrabImageMonocular/RGBD/Stereo() → System::TrackMonocular/RGBD/Stereo() → Main()
  • Tracking::UpdateLocalKeyFrames() → Tracking::UpdateLocalMap() → Tracking::TrackLocalMap() → Tracking::Track() → Tracking::GrabImageMonocular/RGBD/Stereo() → System::TrackMonocular/RGBD/Stereo() → Main()

最后,我们以Map类的mbImuIntialized为起点,也可以画出调用关系图,如下所示。

4.3 总结

我们也可以将上面赋值和调用这两部分合在一起,如下所示,则表示了ORB-SLAM3中完整的对于IMU初始化状态的修改与访问。 至此,我们便对ORB-SLAM3中IMU初始化状态相关内容进行了简单分析。

本文作者原创,未经许可不得转载,谢谢配合

返回顶部