进行相邻帧的位姿估计和局部稀疏地图构建
更多...
#include <frontend.h>
|
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Frontend > | Ptr |
| |
◆ Frontend() [1/2]
◆ Frontend() [2/2]
◆ addFrame()
| void Frontend::addFrame |
( |
const Frame::Ptr & |
frame | ) |
|
◆ detectOutlier()
| int Frontend::detectOutlier |
( |
std::vector< Feature::Ptr > & |
features, |
|
|
std::vector< PoseEdge * > & |
edges, |
|
|
g2o::SparseOptimizer & |
optimizer, |
|
|
PoseVertex * |
vertex |
|
) |
| |
- 注解
- 这里MapPoint的m_isOutlier在这里进行辅助,需要恢复为false
◆ estimatePose()
| int Frontend::estimatePose |
( |
| ) |
|
根据前端追踪的结果进行位姿估计和异常值检测
- 返回
- int 返回m_currFrame关联的MapPoint非异常值的数量
◆ getInstance()
| static Ptr Frontend::getInstance |
( |
| ) |
|
|
inlinestatic |
◆ initTrack()
| void Frontend::initTrack |
( |
| ) |
|
为前端开启循环做m_refFrame的准备
- 注解
- 注意这里需要线程停滞100us,来等待开启后端的优化线程
◆ operator=()
◆ run()
前端启动线程
- 注解
- 需要考虑在关闭前端后,后端一直wait的状态
◆ setCamera()
◆ setDataset()
◆ setMap()
| void Frontend::setMap |
( |
const Map::Ptr & |
map | ) |
|
|
inline |
◆ setViewer()
◆ track()
◆ trackCurrFrame()
| int Frontend::trackCurrFrame |
( |
| ) |
|
追踪m_refFrame中的特征点到m_currFrame
- 注解
- track部分并不维护Feature与MapPoint的关系(非关键帧)
- 返回
- int 返回track成功的二维点数量
- 注解
- Frontend维护m_diffPose来给当前帧追踪赋初值
◆ triangulate()
| bool Frontend::triangulate |
( |
const std::vector< SE3d > & |
poses, |
|
|
const std::vector< Vec2d > & |
pixelPoints, |
|
|
Vec3d & |
worldPoint |
|
) |
| |
- 参数
-
位姿列表
- 参数
-
像素点列表
- 参数
-
三角化计算的结果
- 返回
- true 最小奇异值接近0(存在非零解),并且三角化坐标点z值大于零,三角化成功
-
false 最小奇异值不满足条件,三角化失败
◆ triNewPoint()
三角化新的点
维护Feature和MapPoint之间的关系
- Feature的m_mappoint指向MapPoint
- MapPoint的m_featureNum递增
- 参数
-
新三角化的点集合 - 参数
-
- 返回
- int 返回三角测量后,Frame中可用的MapPoint数目
- 注解
- 将关键帧中可以使用的MapPoint中的m_featureNum增加
◆ m_camera
◆ m_currFrame
◆ m_dataset
◆ m_diffPose
| SE3d Frontend::m_diffPose |
|
private |
◆ m_isStop
| bool Frontend::m_isStop = false |
|
private |
◆ m_map
◆ m_refFrame
◆ m_status
◆ m_viewer
◆ Ptr
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr<Frontend> Frontend::Ptr |
该类的文档由以下文件生成: