载入中...
搜索中...
未找到
Frontend类 参考

进行相邻帧的位姿估计和局部稀疏地图构建 更多...

#include <frontend.h>

Public 成员函数

 Frontend (const Frontend &)=delete
 
Frontendoperator= (const Frontend &)=delete
 
void run ()
 前端启动线程
 
void addFrame (const Frame::Ptr &frame)
 
bool triangulate (const std::vector< SE3d > &poses, const std::vector< Vec2d > &pixelPoints, Vec3d &worldPoint)
 
int triNewPoint (Frame::Ptr &frame, std::vector< MapPoint::Ptr > &newPoints)
 三角化新的点
 
void setCamera (const Camera::Ptr &camera)
 
void setMap (const Map::Ptr &map)
 
void setDataset (const Dataset::Ptr &dataset)
 
void setViewer (const Viewer::Ptr &viewer)
 
int trackCurrFrame ()
 追踪m_refFrame中的特征点到m_currFrame
 
void initTrack ()
 为前端开启循环做m_refFrame的准备
 
int estimatePose ()
 根据前端追踪的结果进行位姿估计和异常值检测
 
int detectOutlier (std::vector< Feature::Ptr > &features, std::vector< PoseEdge * > &edges, g2o::SparseOptimizer &optimizer, PoseVertex *vertex)
 
void track ()
 

静态 Public 成员函数

static Ptr getInstance ()
 

Public 属性

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< FrontendPtr
 

Private 成员函数

 Frontend ()=default
 

Private 属性

Frame::Ptr m_refFrame
 参考帧,左图提供待追踪的Feature
 
Frame::Ptr m_currFrame
 当前帧,参考参考帧进行Feature追踪
 
bool m_isStop = false
 前端线程结束标识
 
Camera::Ptr m_camera
 相机参数
 
Dataset::Ptr m_dataset
 数据集
 
Map::Ptr m_map
 地图
 
SE3d m_diffPose
 上次位姿估计的位姿差Tcr
 
Viewer::Ptr m_viewer
 可视化
 
TrackStatus m_status = TrackStatus::INIT_TRACKING
 

详细描述

进行相邻帧的位姿估计和局部稀疏地图构建

构造及析构函数说明

◆ Frontend() [1/2]

Frontend::Frontend ( const Frontend )
delete

◆ Frontend() [2/2]

Frontend::Frontend ( )
privatedefault

成员函数说明

◆ 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=()

Frontend & Frontend::operator= ( const Frontend )
delete

◆ run()

void Frontend::run ( )

前端启动线程

注解
需要考虑在关闭前端后,后端一直wait的状态

◆ setCamera()

void Frontend::setCamera ( const Camera::Ptr camera)
inline

◆ setDataset()

void Frontend::setDataset ( const Dataset::Ptr dataset)
inline

◆ setMap()

void Frontend::setMap ( const Map::Ptr map)
inline

◆ setViewer()

void Frontend::setViewer ( const Viewer::Ptr viewer)
inline

◆ track()

void Frontend::track ( )
inline
注解
维护位姿差m_diffPose

◆ 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 
)
参数
[in]

位姿列表

参数
[in]

像素点列表

参数
[out]

三角化计算的结果

返回
true 最小奇异值接近0(存在非零解),并且三角化坐标点z值大于零,三角化成功
false 最小奇异值不满足条件,三角化失败

◆ triNewPoint()

int Frontend::triNewPoint ( Frame::Ptr frame,
std::vector< MapPoint::Ptr > &  newPoints 
)

三角化新的点

维护Feature和MapPoint之间的关系

  1. Feature的m_mappoint指向MapPoint
  2. MapPoint的m_featureNum递增
    参数
    [out]
    新三角化的点集合
    参数
    [inand out]frame:需要三角化的帧
    返回
    int 返回三角测量后,Frame中可用的MapPoint数目
注解
将关键帧中可以使用的MapPoint中的m_featureNum增加

类成员变量说明

◆ m_camera

Camera::Ptr Frontend::m_camera
private

相机参数

◆ m_currFrame

Frame::Ptr Frontend::m_currFrame
private

当前帧,参考参考帧进行Feature追踪

◆ m_dataset

Dataset::Ptr Frontend::m_dataset
private

数据集

◆ m_diffPose

SE3d Frontend::m_diffPose
private

上次位姿估计的位姿差Tcr

◆ m_isStop

bool Frontend::m_isStop = false
private

前端线程结束标识

◆ m_map

Map::Ptr Frontend::m_map
private

地图

◆ m_refFrame

Frame::Ptr Frontend::m_refFrame
private

参考帧,左图提供待追踪的Feature

◆ m_status

TrackStatus Frontend::m_status = TrackStatus::INIT_TRACKING
private

◆ m_viewer

Viewer::Ptr Frontend::m_viewer
private

可视化

◆ Ptr

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr<Frontend> Frontend::Ptr

该类的文档由以下文件生成: